ros2_control - rolling
|
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 ¶m_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 ¶m_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 > ¶meters, 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 ¶m_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 > ¶meters, 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. | |
|
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.
[in] | joint_name | Name of the joint whose limits should be checked. |
[in] | parameters | List of the parameters that should be checked if they belong to this structure and that are used for updating the internal values. |
[in] | logging_itf | node logging interface to provide log errors. |
[out] | updated_limits | structure with updated JointLimits. It is recommended that the currently used limits are stored into this structure before calling this method. |
|
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.
[in] | joint_name | Name of the joint whose limits should be checked. |
[in] | parameters | List of the parameters that should be checked if they belong to this structure and that are used for updating the internal values. |
[in] | logging_itf | node logging interface to provide log errors. |
[out] | updated_limits | structure with updated SoftJointLimits. It is recommended that the currently used limits are stored into this structure before calling this method. |
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.
limits | The joint limits. |
desired_acceleration | The desired acceleration. |
actual_velocity | The actual velocity of the joint. |
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.
limits | The joint limits. |
act_pos | The actual position of the joint. |
act_vel | The actual velocity of the joint. |
dt | The time step. |
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.
limits | The joint limits. |
act_vel | The actual velocity of the joint. |
prev_command_pos | The previous commanded position of the joint. |
dt | The time step. |
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.
joint_name | The name of the joint. |
limits | The joint limits. |
act_pos | The actual position of the joint. |
prev_command_vel | The previous commanded velocity of the joint. |
dt | The time step. |
|
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.
[in] | joint_name | name of the joint for which parameters will be declared. |
[in] | node | node for parameters should be declared. |
|
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
:
[in] | joint_name | name of the joint for which parameters will be declared. |
[in] | param_itf | node parameters interface object to access parameters. |
[in] | logging_itf | node logging interface to log if error happens. |
|
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.
[in] | joint_name | name of the joint for which parameters will be declared. |
[in] | lifecycle_node | lifecycle node for parameters should be declared. |
|
inline |
Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits
function.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | node | Node object for which parameters should be fetched. |
[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. |
|
inline |
Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits
function.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | node | Node object for which parameters should be fetched. |
[out] | soft_limits | Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values. |
|
inline |
Populate a JointLimits instance from the node parameters.
It is assumed that parameter structure is the following:
Unspecified parameters are not added to the joint limits specification. A specification in a yaml would look like this:
[in] | joint_name | Name of joint whose limits are to be fetched, e.g., "foo_joint". |
[in] | param_itf | node parameters interface of the node where parameters are specified. |
[in] | logging_itf | node logging interface to provide log errors. |
[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 SoftJointLimits instance from the ROS parameter server.
It is assumed that the parameter structure is the following:
Only completely specified soft joint limits specifications will be considered valid. For example a valid yaml configuration would look like:
[in] | joint_name | Name of joint whose limits are to be fetched, e.g., "foo_joint". |
[in] | param_itf | node parameters interface of the node where parameters are specified. |
[in] | logging_itf | node logging interface to provide log errors. |
[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 JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits
function.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | lifecycle_node | Lifecycle node object for which parameters should be fetched. |
[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. |
|
inline |
Populate a JointLimits instance from the node parameters. This is a convenience function. For parameters structure see the underlying get_joint_limits
function.
[in] | joint_name | Name of joint whose limits are to be fetched. |
[in] | lifecycle_node | Lifecycle node object for which parameters should be fetched. |
[out] | soft_limits | Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite existing values. |
|
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 URDF joint data.
[in] | urdf_joint | URDF joint. |
[out] | soft_limits | Where URDF soft joint limit data gets written into. |
bool joint_limits::is_limited | ( | double | value, |
double | min, | ||
double | max | ||
) |
Checks if a value is limited by the given limits.
value | The value to check. |
min | The minimum limit. |
max | The maximum limit. |