40#include <rclcpp/rclcpp.hpp>
81 const std::string& param_namespace,
82 const std::vector<const moveit::core::JointModel*>& joint_models);
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
AggregationBoundsViolationException(const std::string &error_desc)
A base class for all aggregation exceptions inheriting from std::runtime_exception.
AggregationException(const std::string &error_desc)
Unifies the joint limits from the given joint models with joint limits from the node parameters.
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_mo...
static void updateVelocityLimitFromJointModel(const moveit::core::JointModel *joint_model, JointLimit &joint_limit)
Update the velocity limit with the one from the joint_model.
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 combina...
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 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_mode...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
Extends joint_limits_interface::JointLimits with a deceleration parameter.