44 namespace joint_limits_interface
 
   50                               const rclcpp::Node::SharedPtr& node)
 
   57 inline bool getJointLimits(
const std::string& joint_name, 
const std::string& param_ns,
 
   69     const std::string param_base_name = (param_ns.empty() ? 
"" : param_ns + 
".") + 
"joint_limits." + joint_name;
 
   75           node->declare_parameter(param_base_name + 
".max_deceleration", std::numeric_limits<double>::quiet_NaN());
 
   78   catch (
const std::exception& ex)
 
   80     RCLCPP_WARN_STREAM(node->get_logger(), 
"Failed loading deceleration limits");
 
bool get_joint_limits(const std::string &joint_name, const rclcpp::Node::SharedPtr &node, const std::string ¶m_ns, JointLimits &limits)
Populate a JointLimits instance from the ROS parameter server.
 
bool declare_parameters(const std::string &joint_name, const rclcpp::Node::SharedPtr &node, const std::string ¶m_ns)
 
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)
 
Extends joint_limits_interface::JointLimits with a deceleration parameter.
 
bool has_deceleration_limits
 
double max_deceleration
maximum deceleration MUST(!) be negative