30 #ifndef JOINT_LIMITS_INTERFACE_JOINT_LIMITS_URDF_H 31 #define JOINT_LIMITS_INTERFACE_JOINT_LIMITS_URDF_H 33 #include <ros/common.h> 34 #include <urdf_model/joint.h> 35 #include <urdf/urdfdom_compatibility.h> 50 if (!urdf_joint || !urdf_joint->limits)
55 limits.
has_position_limits = urdf_joint->type == urdf::Joint::REVOLUTE || urdf_joint->type == urdf::Joint::PRISMATIC;
73 limits.
max_effort = urdf_joint->limits->effort;
86 if (!urdf_joint || !urdf_joint->safety)
91 soft_limits.
min_position = urdf_joint->safety->soft_lower_limit;
92 soft_limits.
max_position = urdf_joint->safety->soft_upper_limit;
93 soft_limits.
k_position = urdf_joint->safety->k_position;
94 soft_limits.
k_velocity = urdf_joint->safety->k_velocity;
bool getSoftJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, SoftJointLimits &soft_limits)
Populate a SoftJointLimits instance from the ROS parameter server.
bool getJointLimits(const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits)
Populate a JointLimits instance from the ROS parameter server.
bool has_acceleration_limits