![]() |
ros2_control - galactic
|
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) |
|
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.
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] | node | 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 node
), false otherwise.
|
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. |
|
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.
This specification is similar to the specification of the safety_controller tag in the URDF, adapted to the parameter server.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | node | NodeHandle where the joint limits are specified. |
[out] | soft_limits | Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values. |
k_position
, k_velocity
, soft_lower_limit
and soft_upper_limit
exist in joint_limits/joint_name
namespace), false otherwise.
|
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. |