Namespaces | |
namespace | internal |
Classes | |
class | EffortJointSaturationHandle |
A handle used to enforce position, velocity, and effort limits of an effort-controlled joint that does not have soft limits. More... | |
class | EffortJointSaturationInterface |
class | EffortJointSoftLimitsHandle |
A handle used to enforce position, velocity and effort limits of an effort-controlled joint. More... | |
class | EffortJointSoftLimitsInterface |
struct | JointLimits |
class | JointLimitsInterface |
Interface for enforcing joint limits. More... | |
class | JointLimitsInterfaceException |
An exception related to a JointLimitsInterface. More... | |
class | PositionJointSaturationHandle |
A handle used to enforce position and velocity limits of a position-controlled joint that does not have soft limits. More... | |
class | PositionJointSaturationInterface |
class | PositionJointSoftLimitsHandle |
A handle used to enforce position and velocity limits of a position-controlled joint. More... | |
class | PositionJointSoftLimitsInterface |
struct | SoftJointLimits |
class | VelocityJointSaturationHandle |
A handle used to enforce velocity and acceleration limits of a velocity-controlled joint. More... | |
class | VelocityJointSaturationInterface |
class | VelocityJointSoftLimitsHandle |
A handle used to enforce position, velocity, and acceleration limits of a velocity-controlled joint. More... | |
class | VelocityJointSoftLimitsInterface |
Functions | |
bool | getJointLimits (urdf::JointConstSharedPtr urdf_joint, JointLimits &limits) |
Populate a JointLimits instance from URDF joint data. | |
bool | getJointLimits (const std::string &joint_name, const ros::NodeHandle &nh, JointLimits &limits) |
Populate a JointLimits instance from the ROS parameter server. | |
bool | getSoftJointLimits (urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits) |
Populate a SoftJointLimits instance from URDF joint data. |
bool joint_limits_interface::getJointLimits | ( | urdf::JointConstSharedPtr | urdf_joint, |
JointLimits & | limits | ||
) | [inline] |
Populate a JointLimits instance from URDF joint data.
[in] | urdf_joint | URDF joint. |
[out] | limits | Where URDF joint limit data gets written into. Limits in urdf_joint will overwrite existing values. Values in limits not present in urdf_joint remain unchanged. |
Definition at line 48 of file joint_limits_urdf.h.
bool joint_limits_interface::getJointLimits | ( | const std::string & | joint_name, |
const ros::NodeHandle & | nh, | ||
JointLimits & | limits | ||
) | [inline] |
Populate a JointLimits instance from the ROS parameter server.
It is assumed that the following parameter structure is followed on the provided NodeHandle. Unspecified parameters are simply not added to the joint limits specification.
joint_limits: foo_joint: has_position_limits: true min_position: 0.0 max_position: 1.0 has_velocity_limits: true max_velocity: 2.0 has_acceleration_limits: true max_acceleration: 5.0 has_jerk_limits: true max_jerk: 100.0 has_effort_limits: true max_effort: 20.0 bar_joint: has_position_limits: false # Continuous joint has_velocity_limits: true max_velocity: 4.0
This specification is similar to the one used by MoveIt!, but additionally supports jerk and effort limits.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | nh | NodeHandle where the joint limits are specified. |
[out] | limits | Where joint limit data gets written into. Limits specified in the parameter server will overwrite existing values. Values in limits not specified in the parameter server remain unchanged. |
joint_limits/joint_name
parameter exists in nh
), false otherwise. Definition at line 75 of file joint_limits_rosparam.h.
bool joint_limits_interface::getSoftJointLimits | ( | urdf::JointConstSharedPtr | urdf_joint, |
SoftJointLimits & | soft_limits | ||
) | [inline] |
Populate a SoftJointLimits instance from URDF joint data.
[in] | urdf_joint | URDF joint. |
[out] | soft_limits | Where URDF soft joint limit data gets written into. |
Definition at line 84 of file joint_limits_urdf.h.