17 #ifndef JOINT_LIMITS_INTERFACE_EXTENSION_H    18 #define JOINT_LIMITS_INTERFACE_EXTENSION_H    38     const std::string limits_namespace = 
"joint_limits/" + joint_name;
    41       ROS_DEBUG_STREAM(
"No joint limits specification found for joint '" << joint_name <<
    42                        "' in the parameter server (namespace " << nh.
getNamespace() + 
"/" + limits_namespace << 
").");
    59   bool has_deceleration_limits = 
false;
    60   if(limits_nh.
getParam(
"has_deceleration_limits", has_deceleration_limits))
    64     if (has_deceleration_limits && limits_nh.
getParam(
"max_deceleration", max_dec))
    77 #endif // JOINT_LIMITS_INTERFACE_EXTENSION_H 
bool has_deceleration_limits
double max_deceleration
maximum deceleration MUST(!) be negative 
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh,::pilz_extensions::joint_limits_interface::JointLimits &limits)
const std::string & getNamespace() const 
#define ROS_DEBUG_STREAM(args)
bool getParam(const std::string &key, std::string &s) const 
Extends joint_limits_interface::JointLimits with a deceleration parameter. 
bool hasParam(const std::string &key) const 
#define ROS_ERROR_STREAM(args)