moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 ¶m_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: | |
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. | |
static void | updateVelocityLimitFromJointModel (const moveit::core::JointModel *joint_model, JointLimit &joint_limit) |
Update the velocity limit with the one from the joint_model. | |
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. | |
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. | |
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.
|
staticprotected |
Checks if the position limits from the given joint_limit are stricter than the limits of the joint_model. Throws AggregationBoundsViolationException on violation.
joint_model | The joint_model |
joint_limit | The joint_limit |
Definition at line 168 of file joint_limits_aggregator.cpp.
|
staticprotected |
Checks if the velocity limit from the given joint_limit are stricter than the limit of the joint_model. Throws AggregationBoundsViolationException on violation.
joint_model | The joint_model |
joint_limit | The joint_limit |
Definition at line 186 of file joint_limits_aggregator.cpp.
|
static |
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combination are:
node | Node to use for accessing joint limit parameters |
param_namespace | Namespace to use for looking up node parameters |
joint_models | The joint models |
Definition at line 52 of file joint_limits_aggregator.cpp.
|
staticprotected |
Update the position limits with the ones from the joint_model.
If the joint model has no position limit, the value is unchanged.
joint_model | The joint model |
joint_limit | The joint_limit to be filled with new values. |
Definition at line 115 of file joint_limits_aggregator.cpp.
|
staticprotected |
Update the velocity limit with the one from the joint_model.
If the joint model has no velocity limit, the value is unchanged.
joint_model | The joint model |
joint_limit | The joint_limit to be filled with new values. |
Definition at line 144 of file joint_limits_aggregator.cpp.