Class JointSoftLimiter
Defined in File joint_soft_limiter.hpp
Inheritance Relationships
Base Type
public joint_limits::JointSaturationLimiter< JointControlInterfacesData >(Template Class JointSaturationLimiter)
Class Documentation
-
class JointSoftLimiter : public joint_limits::JointSaturationLimiter<JointControlInterfacesData>
Public Functions
-
virtual ~JointSoftLimiter() = default
-
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.
-
virtual bool on_enforce(const JointControlInterfacesData &actual, JointControlInterfacesData &desired, 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.
- Throws:
std::runtime_error – if the actual position is out of bounds if commanding position
- Returns:
true if limits are enforced, otherwise false.
-
inline bool has_soft_position_limits(const joint_limits::SoftJointLimits &soft_joint_limits)
-
inline bool has_soft_limits(const joint_limits::SoftJointLimits &soft_joint_limits)
-
virtual ~JointSoftLimiter() = default