53 const rclcpp::Node::SharedPtr& node,
const std::string& param_namespace,
54 const std::vector<const moveit::core::JointModel*>& joint_models)
58 RCLCPP_INFO_STREAM(getLogger(),
"Reading limits from namespace " << param_namespace);
61 for (
auto joint_model : joint_models)
109 container.
addLimit(joint_model->getName(), joint_limit);
122 RCLCPP_WARN_STREAM(getLogger(),
"no bounds set for joint " << joint_model->
getName());
132 RCLCPP_WARN_STREAM(getLogger(),
"Multi-DOF-Joint '" << joint_model->
getName() <<
"' not supported.");
140 RCLCPP_DEBUG_STREAM(getLogger(),
"Limit(" << joint_model->
getName() <<
" min:" << joint_limit.
min_position
151 RCLCPP_WARN_STREAM(getLogger(),
"no bounds set for joint " << joint_model->
getName());
160 RCLCPP_WARN_STREAM(getLogger(),
"Multi-DOF-Joint '" << joint_model->
getName() <<
"' not supported.");
175 " violates min limit from URDF");
182 " violates max limit from URDF");
193 " violates velocity limit from URDF");
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
bool satisfiesVelocityBounds(const double *values, double margin=0.0) const
Check if the set of velocities for the variables of this joint are within bounds.
const std::string & getName() const
Get the name of the joint.
bool satisfiesPositionBounds(const double *values, double margin=0.0) const
Check if the set of values for the variables of this joint are within bounds.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
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...
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
bool getJointLimits(const std::string &joint_name, const std::string ¶m_ns, const rclcpp::Node::SharedPtr &node, joint_limits_interface::JointLimits &limits)
bool declareParameters(const std::string &joint_name, const std::string ¶m_ns, const rclcpp::Node::SharedPtr &node)
bool has_acceleration_limits
Extends joint_limits_interface::JointLimits with a deceleration parameter.
bool has_deceleration_limits
double max_deceleration
maximum deceleration MUST(!) be negative