35 if (!urdf_joint || !urdf_joint->limits)
40 limits.has_position_limits =
41 urdf_joint->type == urdf::Joint::REVOLUTE || urdf_joint->type == urdf::Joint::PRISMATIC;
42 if (limits.has_position_limits)
44 limits.min_position = urdf_joint->limits->lower;
45 limits.max_position = urdf_joint->limits->upper;
48 if (!limits.has_position_limits && urdf_joint->type == urdf::Joint::CONTINUOUS)
50 limits.angle_wraparound =
true;
53 limits.has_velocity_limits =
true;
54 limits.max_velocity = std::abs(urdf_joint->limits->velocity);
56 limits.has_acceleration_limits =
false;
58 limits.has_effort_limits =
true;
59 limits.max_effort = std::abs(urdf_joint->limits->effort);
72 if (!urdf_joint || !urdf_joint->safety)
77 soft_limits.min_position = urdf_joint->safety->soft_lower_limit;
78 soft_limits.max_position = urdf_joint->safety->soft_upper_limit;
79 soft_limits.k_position = urdf_joint->safety->k_position;
80 soft_limits.k_velocity = urdf_joint->safety->k_velocity;
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
Populate a SoftJointLimits instance from URDF joint data.
Definition joint_limits_urdf.hpp:70
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
Populate a JointLimits instance from URDF joint data.
Definition joint_limits_urdf.hpp:33