17#ifndef JOINT_LIMITS__JOINT_SATURATION_LIMITER_HPP_
18#define JOINT_LIMITS__JOINT_SATURATION_LIMITER_HPP_
23#include "joint_limits/data_structures.hpp"
24#include "joint_limits/joint_limiter_interface.hpp"
25#include "rclcpp/clock.hpp"
26#include "rclcpp/duration.hpp"
37template <
typename Jo
intLimitsStateDataType>
49 bool on_configure(
const JointLimitsStateDataType & current_joint_states)
override
51 prev_command_ = current_joint_states;
72 const JointLimitsStateDataType & current_joint_states,
73 JointLimitsStateDataType & desired_joint_states,
const rclcpp::Duration & dt)
override;
82 std::lock_guard<std::mutex> lock(mutex_);
83 prev_command_ = JointLimitsStateDataType();
87 rclcpp::Clock::SharedPtr clock_;
88 JointLimitsStateDataType prev_command_;
92template <
typename Jo
intLimitsStateDataType>
96 clock_ = std::make_shared<rclcpp::Clock>(rclcpp::Clock(RCL_ROS_TIME));
99template <
typename Jo
intLimitsStateDataType>
104template <
typename Jo
intLimitsStateDataType>
Definition joint_limiter_interface.hpp:35
Definition joint_saturation_limiter.hpp:39
JointSaturationLimiter()
Constructor.
Definition joint_saturation_limiter.hpp:93
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....
virtual ~JointSaturationLimiter()
Destructor.
Definition joint_saturation_limiter.hpp:100
bool on_init() override
Method is realized by an implementation.
Definition joint_saturation_limiter.hpp:105
void reset_internals() override
Reset internal states of the limiter.
Definition joint_saturation_limiter.hpp:80
bool on_configure(const JointLimitsStateDataType ¤t_joint_states) override
Method is realized by an implementation.
Definition joint_saturation_limiter.hpp:49
Definition data_structures.hpp:39