moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Functions
joint_limits Namespace Reference

Classes

struct  JointLimits
 
struct  SoftJointLimits
 

Functions

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

Detailed Description

Author
Adolfo Rodriguez Tsouroukdissian

Function Documentation

◆ declareParameters()

bool joint_limits::declareParameters ( const std::string &  joint_name,
const rclcpp::Node::SharedPtr &  node,
const std::string &  param_ns 
)
inline

Definition at line 44 of file joint_limits_rosparam.hpp.

Here is the caller graph for this function:

◆ getJointLimits() [1/2]

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

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.

Definition at line 112 of file joint_limits_rosparam.hpp.

Here is the caller graph for this function:

◆ getJointLimits() [2/2]

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

Definition at line 257 of file joint_limits_rosparam.hpp.