Template Class JointSaturationLimiter

Inheritance Relationships

Base Type

Class Documentation

template<typename LimitsType>
class JointSaturationLimiter : public joint_limits::JointLimiterInterface<LimitsType>

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

JOINT_LIMITS_PUBLIC JointSaturationLimiter()

Constructor.

JOINT_LIMITS_PUBLIC ~JointSaturationLimiter()

Destructor.

inline virtual JOINT_LIMITS_PUBLIC 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 JOINT_LIMITS_PUBLIC bool on_configure (const trajectory_msgs::msg::JointTrajectoryPoint &) 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 JOINT_LIMITS_PUBLIC bool on_enforce (trajectory_msgs::msg::JointTrajectoryPoint &current_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:

  • 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.

virtual 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.

If has_effort_limits is set to false, the limits will be not enforced to a joint.

Parameters:

desired_joint_states[inout] physical quantity that should be adjusted to obey the limits.

Returns:

true if limits are enforced, otherwise false.