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

Classes

struct  JointControlInterfacesData
 
struct  JointInterfacesCommandLimiterData
 
class  JointLimiterInterface
 
struct  JointLimits
 
class  JointSaturationLimiter
 
class  JointSoftLimiter
 
struct  SoftJointLimits
 

Functions

 DEFINE_LIMIT_STRUCT (PositionLimits)
 
 DEFINE_LIMIT_STRUCT (VelocityLimits)
 
 DEFINE_LIMIT_STRUCT (EffortLimits)
 
 DEFINE_LIMIT_STRUCT (AccelerationLimits)
 
bool is_limited (double value, double min, double max)
 Checks if a value is limited by the given limits.
 
PositionLimits compute_position_limits (const joint_limits::JointLimits &limits, const std::optional< double > &act_vel, const std::optional< double > &act_pos, const std::optional< double > &prev_command_pos, double dt)
 Computes the position limits based on the velocity and acceleration limits.
 
VelocityLimits compute_velocity_limits (const std::string &joint_name, const joint_limits::JointLimits &limits, const double &desired_vel, const std::optional< double > &act_pos, const std::optional< double > &prev_command_vel, double dt)
 Computes the velocity limits based on the position and acceleration limits.
 
EffortLimits compute_effort_limits (const joint_limits::JointLimits &limits, const std::optional< double > &act_pos, const std::optional< double > &act_vel, double)
 Computes the effort limits based on the position and velocity limits.
 
AccelerationLimits compute_acceleration_limits (const JointLimits &limits, double desired_acceleration, std::optional< double > actual_velocity)
 Computes the acceleration limits based on the change in velocity and acceleration and deceleration limits.
 
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 check_for_limits_update (const std::string &joint_name, const std::vector< rclcpp::Parameter > &parameters, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &updated_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)
 
bool check_for_limits_update (const std::string &joint_name, const std::vector< rclcpp::Parameter > &parameters, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, SoftJointLimits &updated_limits)
 
bool getJointLimits (urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
 Populate a JointLimits instance from URDF joint data.
 
bool getSoftJointLimits (urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
 Populate a SoftJointLimits instance from URDF joint data.
 

Detailed Description

Author
Denis Stogl
Adolfo Rodriguez Tsouroukdissian
AdriĆ  Roig Moreno
Dr. Denis Stogl
Sai Kishor Kothakota

Function Documentation

◆ check_for_limits_update() [1/2]

bool joint_limits::check_for_limits_update ( const std::string &  joint_name,
const std::vector< rclcpp::Parameter > &  parameters,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &  logging_itf,
JointLimits updated_limits 
)
inline

Check if any of updated parameters are related to JointLimits.

This method is intended to be used in the parameters update callback. It is recommended that it's result is temporarily stored and synchronized with the JointLimits structure in the main loop.

Parameters
[in]joint_nameName of the joint whose limits should be checked.
[in]parametersList of the parameters that should be checked if they belong to this structure and that are used for updating the internal values.
[in]logging_itfnode logging interface to provide log errors.
[out]updated_limitsstructure with updated JointLimits. It is recommended that the currently used limits are stored into this structure before calling this method.

◆ check_for_limits_update() [2/2]

bool joint_limits::check_for_limits_update ( const std::string &  joint_name,
const std::vector< rclcpp::Parameter > &  parameters,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &  logging_itf,
SoftJointLimits updated_limits 
)
inline

Check if any of updated parameters are related to SoftJointLimits.

This method is intended to be used in the parameters update callback. It is recommended that it's result is temporarily stored and synchronized with the SoftJointLimits structure in the main loop.

Parameters
[in]joint_nameName of the joint whose limits should be checked.
[in]parametersList of the parameters that should be checked if they belong to this structure and that are used for updating the internal values.
[in]logging_itfnode logging interface to provide log errors.
[out]updated_limitsstructure with updated SoftJointLimits. It is recommended that the currently used limits are stored into this structure before calling this method.

◆ compute_acceleration_limits()

AccelerationLimits joint_limits::compute_acceleration_limits ( const JointLimits limits,
double  desired_acceleration,
std::optional< double >  actual_velocity 
)

Computes the acceleration limits based on the change in velocity and acceleration and deceleration limits.

Parameters
limitsThe joint limits.
desired_accelerationThe desired acceleration.
actual_velocityThe actual velocity of the joint.
Returns
The acceleration limits, first is the lower limit and second is the upper limit.

◆ compute_effort_limits()

EffortLimits joint_limits::compute_effort_limits ( const joint_limits::JointLimits limits,
const std::optional< double > &  act_pos,
const std::optional< double > &  act_vel,
double   
)

Computes the effort limits based on the position and velocity limits.

Parameters
limitsThe joint limits.
act_posThe actual position of the joint.
act_velThe actual velocity of the joint.
dtThe time step.
Returns
The effort limits, first is the lower limit and second is the upper limit.

◆ compute_position_limits()

PositionLimits joint_limits::compute_position_limits ( const joint_limits::JointLimits limits,
const std::optional< double > &  act_vel,
const std::optional< double > &  act_pos,
const std::optional< double > &  prev_command_pos,
double  dt 
)

Computes the position limits based on the velocity and acceleration limits.

Parameters
limitsThe joint limits.
act_velThe actual velocity of the joint.
prev_command_posThe previous commanded position of the joint.
dtThe time step.
Returns
The position limits, first is the lower limit and second is the upper limit.

◆ compute_velocity_limits()

VelocityLimits joint_limits::compute_velocity_limits ( const std::string &  joint_name,
const joint_limits::JointLimits limits,
const double &  desired_vel,
const std::optional< double > &  act_pos,
const std::optional< double > &  prev_command_vel,
double  dt 
)

Computes the velocity limits based on the position and acceleration limits.

Parameters
joint_nameThe name of the joint.
limitsThe joint limits.
act_posThe actual position of the joint.
prev_command_velThe previous commanded velocity of the joint.
dtThe time step.
Returns
The velocity limits, first is the lower limit and second is the upper limit.

◆ 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_deceleration_limits: bool
max_deceleration: 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_deceleration_limits: bool
max_deceleration: 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_deceleration_limits: true
max_deceleration: 7.5
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 data_structures.hpp:37
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.

◆ getJointLimits()

bool joint_limits::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()

bool joint_limits::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.

◆ is_limited()

bool joint_limits::is_limited ( double  value,
double  min,
double  max 
)

Checks if a value is limited by the given limits.

Parameters
valueThe value to check.
minThe minimum limit.
maxThe maximum limit.
Returns
True if the value is limited, false otherwise.