moveit2
The MoveIt Motion Planning Framework for ROS 2.
Static Public Member Functions | List of all members
pilz_industrial_motion_planner::CartesianLimitsAggregator Class Reference

Obtains cartesian limits from the node parameters. More...

#include <cartesian_limits_aggregator.h>

Static Public Member Functions

static CartesianLimit getAggregatedLimits (const rclcpp::Node::SharedPtr &node, const std::string &param_namespace)
 Loads cartesian limits from the node parameters. More...
 

Detailed Description

Obtains cartesian limits from the node parameters.

Definition at line 45 of file cartesian_limits_aggregator.h.

Member Function Documentation

◆ getAggregatedLimits()

pilz_industrial_motion_planner::CartesianLimit CartesianLimitsAggregator::getAggregatedLimits ( const rclcpp::Node::SharedPtr &  node,
const std::string &  param_namespace 
)
static

Loads cartesian limits from the node parameters.

The parameters are expected to be under "~/cartesian_limits" of the given node handle. The following limits can be specified:

  • "max_trans_vel", the maximum translational velocity [m/s]
  • "max_trans_acc, the maximum translational acceleration [m/s^2] - "max_trans_dec", the maximum translational deceleration (<= 0) [m/s^2] - "max_rot_vel", the maximum rotational velocity [rad/s] - "max_rot_acc", the maximum rotational acceleration [rad/s^2] - "max_rot_dec", the maximum rotational deceleration (<= 0)[rad/s^2]
    Parameters
    nodenode to access the parameters
    param_namespacethe parameter name to access the parameters
    Returns
    the obtained cartesian limits

Definition at line 79 of file cartesian_limits_aggregator.cpp.

Here is the caller graph for this function:

The documentation for this class was generated from the following files: