Function joint_limits::get_joint_limits(const std::string&, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr&, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr&, JointLimits&)
Defined in File joint_limits_rosparam.hpp
Function Documentation
-
inline bool joint_limits::get_joint_limits(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &limits)
Populate a JointLimits instance from the node parameters.
It is assumed that parameter structure is the following:
has_position_limits: bool min_position: double max_position: double has_velocity_limits: bool max_velocity: double has_acceleration_limits: bool max_acceleration: double has_deceleration_limits: bool max_deceleration: double has_jerk_limits: bool max_jerk: double has_effort_limits: bool max_effort: double angle_wraparound: bool # will be ignored if there are position limits
Unspecified parameters are not added to the joint limits specification. A specification in a yaml would look like this:
<node_name> ros__parameters: joint_limits: foo_joint: has_position_limits: true min_position: 0.0 max_position: 1.0 has_velocity_limits: true max_velocity: 2.0 has_acceleration_limits: true max_acceleration: 5.0 has_deceleration_limits: true max_deceleration: 7.5 has_jerk_limits: true max_jerk: 100.0 has_effort_limits: true max_effort: 20.0 bar_joint: has_position_limits: false # Continuous joint angle_wraparound: true # available only for continuous joints has_velocity_limits: true max_velocity: 4.0
- Parameters:
joint_name – [in] Name of joint whose limits are to be fetched, e.g., “foo_joint”.
param_itf – [in] node parameters interface of the node where parameters are specified.
logging_itf – [in] node logging interface to provide log errors.
limits – [out] Where joint limit data gets written into. Limits specified in the parameter server will overwrite existing values. Values in
limits
not specified in the parameter server remain unchanged.
- Returns:
True if a limits specification is found (i.e., the
joint_limits/joint_name
parameter exists innode
), false otherwise.