ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
joint_limits::JointSaturationLimiter< JointLimitsStateDataType > Class Template Reference

#include <joint_saturation_limiter.hpp>

Inheritance diagram for joint_limits::JointSaturationLimiter< JointLimitsStateDataType >:
Inheritance graph
[legend]
Collaboration diagram for joint_limits::JointSaturationLimiter< JointLimitsStateDataType >:
Collaboration graph
[legend]

Public Member Functions

 JointSaturationLimiter ()
 Constructor.
 
 ~JointSaturationLimiter ()
 Destructor.
 
bool on_init () override
 Method is realized by an implementation.
 
bool on_configure (const JointLimitsStateDataType &current_joint_states) override
 Method is realized by an implementation.
 
bool on_enforce (const JointLimitsStateDataType &current_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt) override
 Enforce joint limits to desired position, velocity and acceleration using clamping. Class implements this method accepting following data types:
 
bool on_init ()
 Method is realized by an implementation.
 
bool on_enforce (const JointControlInterfacesData &actual, JointControlInterfacesData &desired, const rclcpp::Duration &dt)
 
bool on_enforce (const trajectory_msgs::msg::JointTrajectoryPoint &current_joint_states, trajectory_msgs::msg::JointTrajectoryPoint &desired_joint_states, const rclcpp::Duration &dt)
 
- Public Member Functions inherited from joint_limits::JointLimiterInterface< JointLimitsStateDataType >
virtual bool 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")
 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 &param_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 &current_joint_states)
 
virtual bool enforce (const JointLimitsStateDataType &current_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)
 Enforce joint limits to desired joint state for multiple physical quantities.
 

Protected Attributes

rclcpp::Clock::SharedPtr clock_
 
JointLimitsStateDataType prev_command_
 
- Protected Attributes inherited from joint_limits::JointLimiterInterface< JointLimitsStateDataType >
size_t number_of_joints_
 
std::vector< std::string > joint_names_
 
std::vector< joint_limits::JointLimitsjoint_limits_
 
std::vector< joint_limits::SoftJointLimitssoft_joint_limits_
 
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_
 
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_
 

Additional Inherited Members

- Protected Member Functions inherited from joint_limits::JointLimiterInterface< JointLimitsStateDataType >
bool has_logging_interface () const
 Checks if the logging interface is set.
 
bool has_parameter_interface () const
 Checks if the parameter interface is set.
 

Detailed Description

template<typename JointLimitsStateDataType>
class joint_limits::JointSaturationLimiter< JointLimitsStateDataType >

Joint Saturation Limiter limits joints' position, velocity and acceleration by clamping values to its minimal and maximal allowed values. Since the position, velocity and accelerations are variables in physical relation, it might be that some values are limited lower then specified limit. For example, if a joint is close to its position limit, velocity and acceleration will be reduced accordingly.

Member Function Documentation

◆ on_configure()

template<typename JointLimitsStateDataType >
bool joint_limits::JointSaturationLimiter< JointLimitsStateDataType >::on_configure ( const JointLimitsStateDataType &  current_joint_states)
inlineoverridevirtual

Method is realized by an implementation.

Implementation-specific configuration of limiter's internal states and libraries.

Returns
true if initialization was successful, otherwise false.

Implements joint_limits::JointLimiterInterface< JointLimitsStateDataType >.

◆ on_enforce()

template<typename JointLimitsStateDataType >
bool joint_limits::JointSaturationLimiter< JointLimitsStateDataType >::on_enforce ( const JointLimitsStateDataType &  current_joint_states,
JointLimitsStateDataType &  desired_joint_states,
const rclcpp::Duration &  dt 
)
overridevirtual

Enforce joint limits to desired position, velocity and acceleration using clamping. Class implements this method accepting following data types:

  • trajectory_msgs::msg::JointTrajectoryPoint: limiting position, velocity and acceleration;

Implementation of saturation approach for joints with position, velocity or acceleration limits and values. First, position limits are checked to adjust desired velocity accordingly, then velocity and finally acceleration. The method support partial existence of limits, e.g., missing position limits for continuous joins.

Parameters
[in]current_joint_statescurrent joint states a robot is in.
[in,out]desired_joint_statesjoint state that should be adjusted to obey the limits.
[in]dttime delta to calculate missing integrals and derivation in joint limits.
Returns
true if limits are enforced, otherwise false.

Implements joint_limits::JointLimiterInterface< JointLimitsStateDataType >.

◆ on_init() [1/2]

Method is realized by an implementation.

Implementation-specific initialization of limiter's internal states and libraries.

Returns
true if initialization was successful, otherwise false.

Implements joint_limits::JointLimiterInterface< JointLimitsStateDataType >.

Reimplemented in joint_limits::JointSoftLimiter.

◆ on_init() [2/2]

template<typename JointLimitsStateDataType >
bool joint_limits::JointSaturationLimiter< JointLimitsStateDataType >::on_init ( )
inlineoverridevirtual

Method is realized by an implementation.

Implementation-specific initialization of limiter's internal states and libraries.

Returns
true if initialization was successful, otherwise false.

Implements joint_limits::JointLimiterInterface< JointLimitsStateDataType >.

Reimplemented in joint_limits::JointSoftLimiter.


The documentation for this class was generated from the following file: