ros2_control - galactic
Loading...
Searching...
No Matches
Classes | Functions
joint_limits_interface Namespace Reference

Classes

class  EffortJointSaturationHandle
 
class  EffortJointSoftLimitsHandle
 A handle used to enforce position, velocity and effort limits of an effort-controlled joint. More...
 
class  JointLimitHandle
 
struct  JointLimits
 
class  JointLimitsInterfaceException
 An exception related to a JointLimitsInterface. More...
 
class  JointSoftLimitsHandle
 
class  PositionJointSaturationHandle
 
class  PositionJointSoftLimitsHandle
 A handle used to enforce position and velocity limits of a position-controlled joint. More...
 
struct  SoftJointLimits
 
class  VelocityJointSaturationHandle
 A handle used to enforce velocity and acceleration limits of a velocity-controlled joint. More...
 
class  VelocityJointSoftLimitsHandle
 

Functions

bool getJointLimits (const std::string &joint_name, const rclcpp::Node::SharedPtr &node, JointLimits &limits)
 Populate a JointLimits instance from the ROS parameter server.
 
bool getSoftJointLimits (const std::string &joint_name, const rclcpp::Node::SharedPtr &node, SoftJointLimits &soft_limits)
 Populate a SoftJointLimits instance from the ROS parameter server.
 
bool getJointLimits (urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
 
bool getSoftJointLimits (urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
 

Detailed Description

Author
Adolfo Rodriguez Tsouroukdissian

Function Documentation

◆ getJointLimits() [1/2]

bool joint_limits_interface::getJointLimits ( const std::string &  joint_name,
const rclcpp::Node::SharedPtr &  node,
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.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]nodeNodeHandle where the joint limits are specified.
[out]limitsWhere 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.
Returns
True if a limits specification is found (ie. the joint_limits/joint_name parameter exists in node), false otherwise.

◆ getJointLimits() [2/2]

bool joint_limits_interface::getJointLimits ( urdf::JointConstSharedPtr  urdf_joint,
JointLimits limits 
)
inline

Populate a JointLimits instance from URDF joint data.

Parameters
[in]urdf_jointURDF joint.
[out]limitsWhere 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.
Returns
True if urdf_joint has a valid limits specification, false otherwise.

◆ getSoftJointLimits() [1/2]

bool joint_limits_interface::getSoftJointLimits ( const std::string &  joint_name,
const rclcpp::Node::SharedPtr &  node,
SoftJointLimits soft_limits 
)
inline

Populate a SoftJointLimits instance from the ROS parameter server.

It is assumed that the following parameter structure is followed on the provided NodeHandle. Only completely specified soft joint limits specifications will be considered valid.

joint_limits:
foo_joint:
soft_lower_limit: 0.0
soft_upper_limit: 1.0
k_position: 10.0
k_velocity: 10.0

This specification is similar to the specification of the safety_controller tag in the URDF, adapted to the parameter server.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]nodeNodeHandle where the joint limits are specified.
[out]soft_limitsWhere soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values.
Returns
True if a complete soft limits specification is found (ie. if all k_position, k_velocity, soft_lower_limit and soft_upper_limit exist in joint_limits/joint_name namespace), false otherwise.

◆ getSoftJointLimits() [2/2]

bool joint_limits_interface::getSoftJointLimits ( urdf::JointConstSharedPtr  urdf_joint,
SoftJointLimits soft_limits 
)
inline

Populate a SoftJointLimits instance from URDF joint data.

Parameters
[in]urdf_jointURDF joint.
[out]soft_limitsWhere URDF soft joint limit data gets written into.
Returns
True if urdf_joint has a valid soft limits specification, false otherwise.