ros2_control - humble
|
Classes | |
struct | JointLimits |
struct | SoftJointLimits |
Functions | |
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 | 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) |
|
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. |