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

Unifies the joint limits from the given joint models with joint limits from the node parameters. More...

#include <joint_limits_aggregator.h>

Static Public Member Functions

static JointLimitsContainer getAggregatedLimits (const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
 Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combination are: More...
 

Static Protected Member Functions

static void updatePositionLimitFromJointModel (const moveit::core::JointModel *joint_model, JointLimit &joint_limit)
 Update the position limits with the ones from the joint_model. More...
 
static void updateVelocityLimitFromJointModel (const moveit::core::JointModel *joint_model, JointLimit &joint_limit)
 Update the velocity limit with the one from the joint_model. More...
 
static void checkPositionBoundsThrowing (const moveit::core::JointModel *joint_model, const JointLimit &joint_limit)
 Checks if the position limits from the given joint_limit are stricter than the limits of the joint_model. Throws AggregationBoundsViolationException on violation. More...
 
static void checkVelocityBoundsThrowing (const moveit::core::JointModel *joint_model, const JointLimit &joint_limit)
 Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_model. Throws AggregationBoundsViolationException on violation. More...
 

Detailed Description

Unifies the joint limits from the given joint models with joint limits from the node parameters.

Does not support MultiDOF joints.

Definition at line 56 of file joint_limits_aggregator.h.

Member Function Documentation

◆ checkPositionBoundsThrowing()

void JointLimitsAggregator::checkPositionBoundsThrowing ( const moveit::core::JointModel joint_model,
const JointLimit joint_limit 
)
staticprotected

Checks if the position limits from the given joint_limit are stricter than the limits of the joint_model. Throws AggregationBoundsViolationException on violation.

Parameters
joint_modelThe joint_model
joint_limitThe joint_limit

Definition at line 165 of file joint_limits_aggregator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkVelocityBoundsThrowing()

void JointLimitsAggregator::checkVelocityBoundsThrowing ( const moveit::core::JointModel joint_model,
const JointLimit joint_limit 
)
staticprotected

Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_model. Throws AggregationBoundsViolationException on violation.

Parameters
joint_modelThe joint_model
joint_limitThe joint_limit

Definition at line 183 of file joint_limits_aggregator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getAggregatedLimits()

pilz_industrial_motion_planner::JointLimitsContainer JointLimitsAggregator::getAggregatedLimits ( const rclcpp::Node::SharedPtr &  node,
const std::string &  param_namespace,
const std::vector< const moveit::core::JointModel * > &  joint_models 
)
static

Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combination are:

  1. Position and velocity limits in the node parameters must be stricter or equal if they are defined.
  2. Limits in the node parameters where the corresponding has_<position|velocity|acceleration|deceleration>_limits are „false“ are considered undefined(see point 1).
  3. Not all joints have to be limited by the node parameters. Selective limitation is possible.
  4. If max_deceleration is unset, it will be set to: max_deceleration = - max_acceleration.
    Note
    The acceleration/deceleration can only be set via the node parameters parameter since they are not supported in the urdf so far.
    Parameters
    nodeNode to use for accessing joint limit parameters
    param_namespaceNamespace to use for looking up node parameters
    joint_modelsThe joint models
    Returns
    Container containing the limits

Definition at line 49 of file joint_limits_aggregator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updatePositionLimitFromJointModel()

void JointLimitsAggregator::updatePositionLimitFromJointModel ( const moveit::core::JointModel joint_model,
JointLimit joint_limit 
)
staticprotected

Update the position limits with the ones from the joint_model.

If the joint model has no position limit, the value is unchanged.

Parameters
joint_modelThe joint model
joint_limitThe joint_limit to be filled with new values.

Definition at line 112 of file joint_limits_aggregator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateVelocityLimitFromJointModel()

void JointLimitsAggregator::updateVelocityLimitFromJointModel ( const moveit::core::JointModel joint_model,
JointLimit joint_limit 
)
staticprotected

Update the velocity limit with the one from the joint_model.

If the joint model has no velocity limit, the value is unchanged.

Parameters
joint_modelThe joint model
joint_limitThe joint_limit to be filled with new values.

Definition at line 141 of file joint_limits_aggregator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

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