Function joint_limits::get_joint_limits(const std::string&, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr&, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr&, SoftJointLimits&)
- 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, SoftJointLimits &soft_limits)
- Populate a SoftJointLimits instance from the ROS parameter server. - It is assumed that the parameter structure is the following: - has_soft_limits: bool k_position: double k_velocity: double soft_lower_limit: double soft_upper_limit: double - Only completely specified soft joint limits specifications will be considered valid. For example a valid yaml configuration would look like: - <node_name> ros__parameters: joint_limits: foo_joint: soft_lower_limit: 0.0 soft_upper_limit: 1.0 k_position: 10.0 k_velocity: 10.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. 
- 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_limitand- soft_upper_limitexist in- joint_limits/joint_namenamespace), false otherwise.