ros2_control - rolling
|
#include <joint_saturation_limiter.hpp>
Public Member Functions | |
JOINT_LIMITS_PUBLIC | JointSaturationLimiter () |
Constructor. | |
JOINT_LIMITS_PUBLIC | ~JointSaturationLimiter () |
Destructor. | |
JOINT_LIMITS_PUBLIC bool | on_init () override |
Method is realized by an implementation. More... | |
JOINT_LIMITS_PUBLIC bool | on_configure (const trajectory_msgs::msg::JointTrajectoryPoint &) override |
Method is realized by an implementation. More... | |
JOINT_LIMITS_PUBLIC bool | on_enforce (trajectory_msgs::msg::JointTrajectoryPoint ¤t_joint_states, trajectory_msgs::msg::JointTrajectoryPoint &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: More... | |
JOINT_LIMITS_PUBLIC bool | on_enforce (std::vector< double > &desired_joint_states) override |
Enforce joint limits to desired arbitrary physical quantity. Additional, commonly used method for enforcing limits by clamping desired input value. The limit is defined in effort limits of the joint::limits/JointLimit structure. More... | |
bool | on_enforce (trajectory_msgs::msg::JointTrajectoryPoint ¤t_joint_states, trajectory_msgs::msg::JointTrajectoryPoint &desired_joint_states, const rclcpp::Duration &dt) |
Method is realized by an implementation. More... | |
bool | on_enforce (std::vector< double > &desired_joint_states) |
Method is realized by an implementation. More... | |
Public Member Functions inherited from joint_limits::JointLimiterInterface< LimitsType > | |
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... | |
Additional Inherited Members | |
Protected Attributes inherited from joint_limits::JointLimiterInterface< LimitsType > | |
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_ |
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.
|
inlineoverridevirtual |
Method is realized by an implementation.
Implementation-specific configuration of limiter's internal states and libraries.
Implements joint_limits::JointLimiterInterface< LimitsType >.
|
virtual |
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.
[in,out] | desired_joint_states | joint state that should be adjusted to obey the limits. |
Implements joint_limits::JointLimiterInterface< LimitsType >.
|
overridevirtual |
Enforce joint limits to desired arbitrary physical quantity. Additional, commonly used method for enforcing limits by clamping desired input value. The limit is defined in effort limits of the joint::limits/JointLimit
structure.
If has_effort_limits
is set to false, the limits will be not enforced to a joint.
[in,out] | desired_joint_states | physical quantity that should be adjusted to obey the limits. |
Implements joint_limits::JointLimiterInterface< LimitsType >.
|
virtual |
Method is realized by an implementation.
Filter-specific implementation of the joint limits enforce algorithm for multiple dependent physical quantities.
[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. |
Implements joint_limits::JointLimiterInterface< LimitsType >.
|
overridevirtual |
Enforce joint limits to desired position, velocity and acceleration using clamping. Class implements this method accepting following data types:
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.
[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. |
Implements joint_limits::JointLimiterInterface< LimitsType >.
|
inlineoverridevirtual |
Method is realized by an implementation.
Implementation-specific initialization of limiter's internal states and libraries.
Implements joint_limits::JointLimiterInterface< LimitsType >.