Template Class JointLimiterInterface
Defined in File joint_limiter_interface.hpp
Inheritance Relationships
Derived Type
public joint_limits::JointSaturationLimiter< LimitsType >
(Template Class JointSaturationLimiter)
Class Documentation
-
template<typename LimitsType>
class JointLimiterInterface Subclassed by joint_limits::JointSaturationLimiter< LimitsType >
Public Functions
-
JOINT_LIMITS_PUBLIC JointLimiterInterface() = default
-
virtual JOINT_LIMITS_PUBLIC ~JointLimiterInterface() = default
- inline 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.
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:
joint_names – [in] names of joints where limits should be applied.
param_itf – [in] node parameters interface object to access parameters.
logging_itf – [in] node logging interface to log if error happens.
robot_description_topic – [in] string of a topic where robot description is accessible.
- inline 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")
Wrapper init method that accepts pointer to the Node. For details see other init method.
- inline 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")
Wrapper init method that accepts pointer to the LifecycleNode. For details see other init method.
- inline virtual JOINT_LIMITS_PUBLIC bool configure (const JointLimitsStateDataType ¤t_joint_states)
- inline 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.
Generic enforce method that calls implementation-specific
on_enforce
method.- Parameters:
current_joint_states – [in] current joint states a robot is in.
desired_joint_states – [inout] joint state that should be adjusted to obey the limits.
dt – [in] time delta to calculate missing integrals and derivation in joint limits.
- Returns:
true if limits are enforced, otherwise false.
- inline virtual JOINT_LIMITS_PUBLIC bool enforce (std::vector< double > &desired_joint_states)
Enforce joint limits to desired joint state for single physical quantity.
Generic enforce method that calls implementation-specific
on_enforce
method.- Parameters:
desired_joint_states – [inout] joint state that should be adjusted to obey the limits.
- Returns:
true if limits are enforced, otherwise false.
Protected Functions
- virtual JOINT_LIMITS_PUBLIC bool on_init ()=0
Method is realized by an implementation.
Implementation-specific initialization of limiter’s internal states and libraries.
- Returns:
true if initialization was successful, otherwise false.
- virtual JOINT_LIMITS_PUBLIC bool on_configure (const JointLimitsStateDataType ¤t_joint_states)=0
Method is realized by an implementation.
Implementation-specific configuration of limiter’s internal states and libraries.
- Returns:
true if initialization was successful, otherwise false.
- 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.
Filter-specific implementation of the joint limits enforce algorithm for multiple dependent physical quantities.
- Parameters:
current_joint_states – [in] current joint states a robot is in.
desired_joint_states – [inout] joint state that should be adjusted to obey the limits.
dt – [in] time delta to calculate missing integrals and derivation in joint limits.
- Returns:
true if limits are enforced, otherwise false.
- virtual JOINT_LIMITS_PUBLIC bool on_enforce (std::vector< double > &desired_joint_states)=0
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:
desired_joint_states – [inout] joint state that should be adjusted to obey the limits.
- Returns:
true if limits are enforced, otherwise false.
-
JOINT_LIMITS_PUBLIC JointLimiterInterface() = default