Function joint_limits::getJointLimits(const std::string&, const rclcpp::Node::SharedPtr&, const std::string&, SoftJointLimits&)

Function Documentation

inline bool joint_limits::getJointLimits(const std::string &joint_name, const rclcpp::Node::SharedPtr &node, const std::string &param_ns, SoftJointLimits &soft_limits)

Populate a SoftJointLimits instance from the ROS parameter server.

It is assumed that the following parameter structure is followed on the provided NodeHandle. Only completely specified soft joint limits specifications will be considered valid.

 joint_limits: foo_joint: soft_lower_limit:
0.0 soft_upper_limit: 1.0 k_position: 10.0 k_velocity: 10.0 

This specification is similar to the specification of the safety_controller tag in the URDF, adapted to the parameter server.

Parameters:
  • joint_name[in] Name of joint whose limits are to be fetched.

  • node[in] NodeHandle where the joint limits are specified.

  • soft_limits[out] Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values.

Returns:

True if a complete soft limits specification is found (ie. if all k_position, k_velocity, soft_lower_limit and soft_upper_limit exist in joint_limits/joint_name namespace), false otherwise.