|
virtual JOINT_LIMITS_PUBLIC bool | init (const std::vector< std::string > &joint_names, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, const std::string &robot_description_topic="/robot_description") |
| Initialization of every JointLimiter. More...
|
|
virtual JOINT_LIMITS_PUBLIC bool | init (const std::vector< std::string > &joint_names, const rclcpp::Node::SharedPtr &node, const std::string &robot_description_topic="/robot_description") |
|
virtual JOINT_LIMITS_PUBLIC bool | init (const std::vector< std::string > &joint_names, const rclcpp_lifecycle::LifecycleNode::SharedPtr &lifecycle_node, const std::string &robot_description_topic="/robot_description") |
|
virtual JOINT_LIMITS_PUBLIC bool | configure (const JointLimitsStateDataType ¤t_joint_states) |
|
virtual JOINT_LIMITS_PUBLIC bool | enforce (JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt) |
| Enforce joint limits to desired joint state for multiple physical quantities. More...
|
|
virtual JOINT_LIMITS_PUBLIC bool | enforce (std::vector< double > &desired_joint_states) |
| Enforce joint limits to desired joint state for single physical quantity. More...
|
|
|
virtual JOINT_LIMITS_PUBLIC bool | on_init ()=0 |
| Method is realized by an implementation. More...
|
|
virtual JOINT_LIMITS_PUBLIC bool | on_configure (const JointLimitsStateDataType ¤t_joint_states)=0 |
| Method is realized by an implementation. More...
|
|
virtual JOINT_LIMITS_PUBLIC bool | on_enforce (JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)=0 |
| Method is realized by an implementation. More...
|
|
virtual JOINT_LIMITS_PUBLIC bool | on_enforce (std::vector< double > &desired_joint_states)=0 |
| Method is realized by an implementation. More...
|
|
|
size_t | number_of_joints_ |
|
std::vector< std::string > | joint_names_ |
|
std::vector< LimitsType > | joint_limits_ |
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr | node_param_itf_ |
|
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr | node_logging_itf_ |
|
◆ enforce() [1/2]
template<typename LimitsType >
virtual JOINT_LIMITS_PUBLIC bool joint_limits::JointLimiterInterface< LimitsType >::enforce |
( |
JointLimitsStateDataType & |
current_joint_states, |
|
|
JointLimitsStateDataType & |
desired_joint_states, |
|
|
const rclcpp::Duration & |
dt |
|
) |
| |
|
inlinevirtual |
Enforce joint limits to desired joint state for multiple physical quantities.
Generic enforce method that calls implementation-specific on_enforce
method.
- Parameters
-
[in] | current_joint_states | current joint states a robot is in. |
[in,out] | desired_joint_states | joint state that should be adjusted to obey the limits. |
[in] | dt | time delta to calculate missing integrals and derivation in joint limits. |
- Returns
- true if limits are enforced, otherwise false.
◆ enforce() [2/2]
template<typename LimitsType >
Enforce joint limits to desired joint state for single physical quantity.
Generic enforce method that calls implementation-specific on_enforce
method.
- Parameters
-
[in,out] | desired_joint_states | joint state that should be adjusted to obey the limits. |
- Returns
- true if limits are enforced, otherwise false.
◆ init() [1/3]
template<typename LimitsType >
virtual JOINT_LIMITS_PUBLIC bool joint_limits::JointLimiterInterface< LimitsType >::init |
( |
const std::vector< std::string > & |
joint_names, |
|
|
const rclcpp::Node::SharedPtr & |
node, |
|
|
const std::string & |
robot_description_topic = "/robot_description" |
|
) |
| |
|
inlinevirtual |
Wrapper init method that accepts pointer to the Node. For details see other init method.
◆ init() [2/3]
template<typename LimitsType >
virtual JOINT_LIMITS_PUBLIC bool joint_limits::JointLimiterInterface< LimitsType >::init |
( |
const std::vector< std::string > & |
joint_names, |
|
|
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & |
param_itf, |
|
|
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & |
logging_itf, |
|
|
const std::string & |
robot_description_topic = "/robot_description" |
|
) |
| |
|
inlinevirtual |
Initialization of every JointLimiter.
Initialization of JointLimiter for defined joints with their names. Robot description topic provides a topic name where URDF of the robot can be found. This is needed to use joint limits from URDF (not implemented yet!). Override this method only if initialization and reading joint limits should be adapted. Otherwise, initialize your custom limiter in on_limit
method.
- Parameters
-
[in] | joint_names | names of joints where limits should be applied. |
[in] | param_itf | node parameters interface object to access parameters. |
[in] | logging_itf | node logging interface to log if error happens. |
[in] | robot_description_topic | string of a topic where robot description is accessible. |
◆ init() [3/3]
template<typename LimitsType >
virtual JOINT_LIMITS_PUBLIC bool joint_limits::JointLimiterInterface< LimitsType >::init |
( |
const std::vector< std::string > & |
joint_names, |
|
|
const rclcpp_lifecycle::LifecycleNode::SharedPtr & |
lifecycle_node, |
|
|
const std::string & |
robot_description_topic = "/robot_description" |
|
) |
| |
|
inlinevirtual |
Wrapper init method that accepts pointer to the LifecycleNode. For details see other init method.
◆ on_configure()
template<typename LimitsType >
Method is realized by an implementation.
Implementation-specific configuration of limiter's internal states and libraries.
- Returns
- true if initialization was successful, otherwise false.
Implemented in joint_limits::JointSaturationLimiter< LimitsType >.
◆ on_enforce() [1/2]
template<typename LimitsType >
virtual JOINT_LIMITS_PUBLIC bool joint_limits::JointLimiterInterface< LimitsType >::on_enforce |
( |
JointLimitsStateDataType & |
current_joint_states, |
|
|
JointLimitsStateDataType & |
desired_joint_states, |
|
|
const rclcpp::Duration & |
dt |
|
) |
| |
|
protectedpure virtual |
Method is realized by an implementation.
Filter-specific implementation of the joint limits enforce algorithm for multiple dependent physical quantities.
- Parameters
-
[in] | current_joint_states | current joint states a robot is in. |
[in,out] | desired_joint_states | joint state that should be adjusted to obey the limits. |
[in] | dt | time delta to calculate missing integrals and derivation in joint limits. |
- Returns
- true if limits are enforced, otherwise false.
Implemented in joint_limits::JointSaturationLimiter< LimitsType >, and joint_limits::JointSaturationLimiter< LimitsType >.
◆ on_enforce() [2/2]
template<typename LimitsType >
Method is realized by an implementation.
Filter-specific implementation of the joint limits enforce algorithm for single physical quantity. This method might use "effort" limits since they are often used as wild-card. Check the documentation of the exact implementation for more details.
- Parameters
-
[in,out] | desired_joint_states | joint state that should be adjusted to obey the limits. |
- Returns
- true if limits are enforced, otherwise false.
Implemented in joint_limits::JointSaturationLimiter< LimitsType >, and joint_limits::JointSaturationLimiter< LimitsType >.
◆ on_init()
template<typename LimitsType >
Method is realized by an implementation.
Implementation-specific initialization of limiter's internal states and libraries.
- Returns
- true if initialization was successful, otherwise false.
Implemented in joint_limits::JointSaturationLimiter< LimitsType >.
The documentation for this class was generated from the following file: