Function joint_limits::declare_parameters(const std::string&, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr&, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr&)

Function Documentation

inline bool joint_limits::declare_parameters(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)

Declare JointLimits and SoftJointLimits parameters for joint with joint_name using node parameters interface param_itf.

The following parameter structure is declared with base name joint_limits.joint_name:

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
has_soft_limits: bool
k_position: double
k_velocity: double
soft_lower_limit: double
soft_upper_limit: double

Parameters:
  • joint_name[in] name of the joint for which parameters will be declared.

  • param_itf[in] node parameters interface object to access parameters.

  • logging_itf[in] node logging interface to log if error happens.

Returns:

True if parameters are successfully declared, false otherwise.