Template Class JointSaturationLimiter
Defined in File joint_saturation_limiter.hpp
Inheritance Relationships
Base Type
public joint_limits::JointLimiterInterface< JointLimitsStateDataType >
(Template Class JointLimiterInterface)
Class Documentation
-
template<typename JointLimitsStateDataType>
class JointSaturationLimiter : public joint_limits::JointLimiterInterface<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.
Public Functions
-
JointSaturationLimiter()
Constructor.
-
~JointSaturationLimiter()
Destructor.
-
inline virtual bool on_init() override
Method is realized by an implementation.
Implementation-specific initialization of limiter’s internal states and libraries.
- Returns:
true if initialization was successful, otherwise false.
-
inline virtual bool on_configure(const JointLimitsStateDataType ¤t_joint_states) override
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 bool on_enforce(const JointLimitsStateDataType ¤t_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:
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:
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.
-
JointSaturationLimiter()