|
virtual 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.
|
|
virtual bool | init (const std::vector< std::string > &joint_names, const std::vector< joint_limits::JointLimits > &joint_limits, const std::vector< joint_limits::SoftJointLimits > &soft_joint_limits, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf) |
|
virtual bool | init (const std::vector< std::string > &joint_names, const rclcpp::Node::SharedPtr &node, const std::string &robot_description_topic="/robot_description") |
|
virtual 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 bool | configure (const JointLimitsStateDataType ¤t_joint_states) |
|
virtual bool | enforce (const JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt) |
| Enforce joint limits to desired joint state for multiple physical quantities.
|
|
|
virtual bool | on_init ()=0 |
| Method is realized by an implementation.
|
|
virtual bool | on_configure (const JointLimitsStateDataType ¤t_joint_states)=0 |
| Method is realized by an implementation.
|
|
virtual bool | on_enforce (const JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)=0 |
| Method is realized by an implementation.
|
|
bool | has_logging_interface () const |
| Checks if the logging interface is set.
|
|
bool | has_parameter_interface () const |
| Checks if the parameter interface is set.
|
|
|
size_t | number_of_joints_ |
|
std::vector< std::string > | joint_names_ |
|
std::vector< joint_limits::JointLimits > | joint_limits_ |
|
std::vector< joint_limits::SoftJointLimits > | soft_joint_limits_ |
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr | node_param_itf_ |
|
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr | node_logging_itf_ |
|
◆ enforce()
template<typename JointLimitsStateDataType >
virtual bool joint_limits::JointLimiterInterface< JointLimitsStateDataType >::enforce |
( |
const 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.
◆ has_logging_interface()
template<typename JointLimitsStateDataType >
Checks if the logging interface is set.
- Returns
- true if the logging interface is available, otherwise false.
- Note
- this way of interfacing would be useful for instances where the logging interface is not available, for example in the ResourceManager or ResourceStorage classes.
◆ has_parameter_interface()
template<typename JointLimitsStateDataType >
Checks if the parameter interface is set.
- Returns
- true if the parameter interface is available, otherwise false.
- Note
- this way of interfacing would be useful for instances where the logging interface is not available, for example in the ResourceManager or ResourceStorage classes.
◆ init() [1/4]
template<typename JointLimitsStateDataType >
virtual bool joint_limits::JointLimiterInterface< JointLimitsStateDataType >::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/4]
template<typename JointLimitsStateDataType >
virtual bool joint_limits::JointLimiterInterface< JointLimitsStateDataType >::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/4]
template<typename JointLimitsStateDataType >
virtual bool joint_limits::JointLimiterInterface< JointLimitsStateDataType >::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.
◆ init() [4/4]
template<typename JointLimitsStateDataType >
Wrapper init method that accepts the joint names and their limits directly
◆ on_configure()
template<typename JointLimitsStateDataType >
◆ on_enforce()
template<typename JointLimitsStateDataType >
virtual bool joint_limits::JointLimiterInterface< JointLimitsStateDataType >::on_enforce |
( |
const 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< JointLimitsStateDataType >.
◆ on_init()
template<typename JointLimitsStateDataType >
The documentation for this class was generated from the following file: