ros2_control - humble
Loading...
Searching...
No Matches
Classes | Functions
joint_limits Namespace Reference

Classes

struct  JointLimits
 
struct  SoftJointLimits
 

Functions

bool declare_parameters (const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)
 
bool declare_parameters (const std::string &joint_name, const rclcpp::Node::SharedPtr &node)
 
bool declare_parameters (const std::string &joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr &lifecycle_node)
 
bool get_joint_limits (const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &limits)
 Populate a JointLimits instance from the node parameters.
 
bool get_joint_limits (const std::string &joint_name, const rclcpp::Node::SharedPtr &node, JointLimits &limits)
 
bool get_joint_limits (const std::string &joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr &lifecycle_node, JointLimits &limits)
 
bool get_joint_limits (const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &param_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, SoftJointLimits &soft_limits)
 Populate a SoftJointLimits instance from the ROS parameter server.
 
bool get_joint_limits (const std::string &joint_name, const rclcpp::Node::SharedPtr &node, SoftJointLimits &soft_limits)
 
bool get_joint_limits (const std::string &joint_name, const rclcpp_lifecycle::LifecycleNode::SharedPtr &lifecycle_node, SoftJointLimits &soft_limits)
 

Detailed Description

Author
Adolfo Rodriguez Tsouroukdissian

Function Documentation

◆ declare_parameters() [1/3]

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

Declare JointLimits and SoftJointLimits parameters for joint with joint_name for the node object. This is a convenience function. For parameters structure see the underlying declare_parameters function.

Parameters
[in]joint_namename of the joint for which parameters will be declared.
[in]nodenode for parameters should be declared.
Returns
True if parameters are successfully declared, false otherwise.

◆ declare_parameters() [2/3]

bool joint_limits::declare_parameters ( const std::string &  joint_name,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  param_itf,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &  logging_itf 
)
inline

Declare JointLimits and SoftJointLimits parameters for joint with joint_name using node parameters interface param_itf.

The following parameter structure is declared with base name joint_limits.joint_name:

has_position_limits: bool
min_position: double
max_position: double
has_velocity_limits: bool
max_velocity: double
has_acceleration_limits: bool
max_acceleration: double
has_jerk_limits: bool
max_jerk: double
has_effort_limits: bool
max_effort: double
angle_wraparound: bool
has_soft_limits: bool
k_position: double
k_velocity: double
soft_lower_limit: double
soft_upper_limit: double
Parameters
[in]joint_namename of the joint for which parameters will be declared.
[in]param_itfnode parameters interface object to access parameters.
[in]logging_itfnode logging interface to log if error happens.
Returns
True if parameters are successfully declared, false otherwise.

◆ declare_parameters() [3/3]

bool joint_limits::declare_parameters ( const std::string &  joint_name,
const rclcpp_lifecycle::LifecycleNode::SharedPtr &  lifecycle_node 
)
inline

Declare JointLimits and SoftJointLimits parameters for joint with joint_name for the lifecycle_node object. This is a convenience function. For parameters structure see the underlying declare_parameters function.

Parameters
[in]joint_namename of the joint for which parameters will be declared.
[in]lifecycle_nodelifecycle node for parameters should be declared.
Returns
True if parameters are successfully declared, false otherwise.

◆ get_joint_limits() [1/6]

bool joint_limits::get_joint_limits ( const std::string &  joint_name,
const rclcpp::Node::SharedPtr &  node,
JointLimits limits 
)
inline

Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits function.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]nodeNode object for which parameters should be fetched.
[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, false otherwise.

◆ get_joint_limits() [2/6]

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

Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits function.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]nodeNode object for which parameters should be fetched.
[out]soft_limitsWhere soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values.
Returns
True if a soft limits specification is found, false otherwise.

◆ get_joint_limits() [3/6]

bool joint_limits::get_joint_limits ( const std::string &  joint_name,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  param_itf,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &  logging_itf,
JointLimits limits 
)
inline

Populate a JointLimits instance from the node parameters.

It is assumed that parameter structure is the following:

has_position_limits: bool
min_position: double
max_position: double
has_velocity_limits: bool
max_velocity: double
has_acceleration_limits: bool
max_acceleration: double
has_jerk_limits: bool
max_jerk: double
has_effort_limits: bool
max_effort: double
angle_wraparound: bool # will be ignored if there are position limits

Unspecified parameters are not added to the joint limits specification. A specification in a yaml would look like this:

<node_name>
ros__parameters:
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
angle_wraparound: true # available only for continuous joints
has_velocity_limits: true
max_velocity: 4.0
Definition joint_limits.hpp:25
Parameters
[in]joint_nameName of joint whose limits are to be fetched, e.g., "foo_joint".
[in]param_itfnode parameters interface of the node where parameters are specified.
[in]logging_itfnode logging interface to provide log errors.
[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 (i.e., the joint_limits/joint_name parameter exists in node), false otherwise.

◆ get_joint_limits() [4/6]

bool joint_limits::get_joint_limits ( const std::string &  joint_name,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  param_itf,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &  logging_itf,
SoftJointLimits soft_limits 
)
inline

Populate a SoftJointLimits instance from the ROS parameter server.

It is assumed that the parameter structure is the following:

has_soft_limits: bool
k_position: double
k_velocity: double
soft_lower_limit: double
soft_upper_limit: double

Only completely specified soft joint limits specifications will be considered valid. For example a valid yaml configuration would look like:

<node_name>
ros__parameters:
foo_joint:
soft_lower_limit: 0.0
soft_upper_limit: 1.0
k_position: 10.0
k_velocity: 10.0
Parameters
[in]joint_nameName of joint whose limits are to be fetched, e.g., "foo_joint".
[in]param_itfnode parameters interface of the node where parameters are specified.
[in]logging_itfnode logging interface to provide log errors.
[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.

◆ get_joint_limits() [5/6]

bool joint_limits::get_joint_limits ( const std::string &  joint_name,
const rclcpp_lifecycle::LifecycleNode::SharedPtr &  lifecycle_node,
JointLimits limits 
)
inline

Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits function.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]lifecycle_nodeLifecycle node object for which parameters should be fetched.
[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, false otherwise.

◆ get_joint_limits() [6/6]

bool joint_limits::get_joint_limits ( const std::string &  joint_name,
const rclcpp_lifecycle::LifecycleNode::SharedPtr &  lifecycle_node,
SoftJointLimits soft_limits 
)
inline

Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits function.

Parameters
[in]joint_nameName of joint whose limits are to be fetched.
[in]lifecycle_nodeLifecycle node object for which parameters should be fetched.
[out]soft_limitsWhere soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values.
Returns
True if a soft limits specification is found, false otherwise.