17#ifndef JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
18#define JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
27#include <hardware_interface/joint_handle.hpp>
28#include <hardware_interface/types/hardware_interface_type_values.hpp>
29#include <rclcpp/duration.hpp>
30#include <rclcpp/rclcpp.hpp>
31#include <rcppmath/clamp.hpp>
33#include "joint_limits_interface/joint_limits.hpp"
34#include "joint_limits_interface/joint_limits_interface_exception.hpp"
46 : prev_pos_(std::numeric_limits<double>::quiet_NaN()),
50 jcmdh_(
"position_command")
55 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
56 const JointLimits & limits)
61 prev_pos_(std::numeric_limits<double>::quiet_NaN()),
67 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jvelh,
68 const hardware_interface::JointHandle & jcmdh,
const JointLimits & limits)
73 prev_pos_(std::numeric_limits<double>::quiet_NaN()),
81 return jposh_ ? jposh_.get_name()
82 : jvelh_ ? jvelh_.get_name()
83 : jcmdh_ ? jcmdh_.get_name()
93 prev_pos_ = std::numeric_limits<double>::quiet_NaN();
98 hardware_interface::JointHandle jposh_;
99 hardware_interface::JointHandle jvelh_;
100 hardware_interface::JointHandle jcmdh_;
101 joint_limits_interface::JointLimits limits_;
116 return jvelh_ ? jvelh_.get_value() : (jposh_.get_value() - prev_pos_) / period.seconds();
129 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
130 const JointLimits & limits,
const SoftJointLimits & soft_limits)
136 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jvelh,
137 const hardware_interface::JointHandle & jcmdh,
const JointLimits & limits,
138 const SoftJointLimits & soft_limits)
144 joint_limits_interface::SoftJointLimits soft_limits_;
155 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
156 const JointLimits & limits)
159 if (limits_.has_position_limits)
161 min_pos_limit_ = limits_.min_position;
162 max_pos_limit_ = limits_.max_position;
166 min_pos_limit_ = -std::numeric_limits<double>::max();
167 max_pos_limit_ = std::numeric_limits<double>::max();
177 if (std::isnan(prev_pos_))
179 prev_pos_ = jposh_.get_value();
182 double min_pos, max_pos;
183 if (limits_.has_velocity_limits)
188 const double delta_pos = limits_.max_velocity * period.seconds();
189 min_pos = std::max(prev_pos_ - delta_pos, min_pos_limit_);
190 max_pos = std::min(prev_pos_ + delta_pos, max_pos_limit_);
195 min_pos = min_pos_limit_;
196 max_pos = max_pos_limit_;
200 const double cmd = rcppmath::clamp(jcmdh_.get_value(), min_pos, max_pos);
201 jcmdh_.set_value(cmd);
207 double min_pos_limit_, max_pos_limit_;
247 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
248 const joint_limits_interface::JointLimits & limits,
249 const joint_limits_interface::SoftJointLimits & soft_limits)
252 if (!limits.has_velocity_limits)
255 "Cannot enforce limits for joint '" +
get_name() +
256 "'. It has no velocity limits specification.");
268 assert(period.seconds() > 0.0);
271 if (std::isnan(prev_pos_))
274 prev_pos_ = jposh_.get_value();
276 const double pos = prev_pos_;
282 if (limits_.has_position_limits)
285 soft_min_vel = rcppmath::clamp(
286 -soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
287 limits_.max_velocity);
289 soft_max_vel = rcppmath::clamp(
290 -soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
291 limits_.max_velocity);
296 soft_min_vel = -limits_.max_velocity;
297 soft_max_vel = limits_.max_velocity;
301 const double dt = period.seconds();
302 double pos_low = pos + soft_min_vel * dt;
303 double pos_high = pos + soft_max_vel * dt;
305 if (limits_.has_position_limits)
309 pos_low = std::max(pos_low, limits_.min_position);
310 pos_high = std::min(pos_high, limits_.max_position);
314 const double pos_cmd = rcppmath::clamp(jcmdh_.get_value(), pos_low, pos_high);
315 jcmdh_.set_value(pos_cmd);
320 prev_pos_ = jcmdh_.get_value();
334 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jvelh,
335 const hardware_interface::JointHandle & jcmdh,
336 const joint_limits_interface::JointLimits & limits)
339 if (!limits.has_velocity_limits)
342 "Cannot enforce limits for joint '" +
get_name() +
343 "'. It has no velocity limits specification.");
345 if (!limits.has_effort_limits)
348 "Cannot enforce limits for joint '" +
get_name() +
349 "'. It has no efforts limits specification.");
354 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
355 const joint_limits_interface::JointLimits & limits)
369 double min_eff = -limits_.max_effort;
370 double max_eff = limits_.max_effort;
372 if (limits_.has_position_limits)
374 const double pos = jposh_.get_value();
375 if (pos < limits_.min_position)
379 else if (pos > limits_.max_position)
386 if (vel < -limits_.max_velocity)
390 else if (vel > limits_.max_velocity)
395 double clamped = rcppmath::clamp(jcmdh_.get_value(), min_eff, max_eff);
396 jcmdh_.set_value(clamped);
408 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jvelh,
409 const hardware_interface::JointHandle & jcmdh,
410 const joint_limits_interface::JointLimits & limits,
411 const joint_limits_interface::SoftJointLimits & soft_limits)
414 if (!limits.has_velocity_limits)
417 "Cannot enforce limits for joint '" +
get_name() +
418 "'. It has no velocity limits specification.");
420 if (!limits.has_effort_limits)
423 "Cannot enforce limits for joint '" +
get_name() +
424 "'. It has no effort limits specification.");
429 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jcmdh,
430 const joint_limits_interface::JointLimits & limits,
431 const joint_limits_interface::SoftJointLimits & soft_limits)
448 const double pos = jposh_.get_value();
455 if (limits_.has_position_limits)
458 soft_min_vel = rcppmath::clamp(
459 -soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
460 limits_.max_velocity);
462 soft_max_vel = rcppmath::clamp(
463 -soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
464 limits_.max_velocity);
469 soft_min_vel = -limits_.max_velocity;
470 soft_max_vel = limits_.max_velocity;
474 const double soft_min_eff = rcppmath::clamp(
475 -soft_limits_.k_velocity * (vel - soft_min_vel), -limits_.max_effort, limits_.max_effort);
477 const double soft_max_eff = rcppmath::clamp(
478 -soft_limits_.k_velocity * (vel - soft_max_vel), -limits_.max_effort, limits_.max_effort);
481 const double eff_cmd = rcppmath::clamp(jcmdh_.get_value(), soft_min_eff, soft_max_eff);
482 jcmdh_.set_value(eff_cmd);
493 const hardware_interface::JointHandle & jvelh,
494 const hardware_interface::JointHandle & jcmdh,
495 const joint_limits_interface::JointLimits & limits)
499 if (!limits.has_velocity_limits)
502 "Cannot enforce limits for joint '" +
get_name() +
503 "'. It has no velocity limits specification.");
508 const hardware_interface::JointHandle & jcmdh,
509 const joint_limits_interface::JointLimits & limits)
514 if (!limits.has_velocity_limits)
517 "Cannot enforce limits for joint '" +
get_name() +
518 "'. It has no velocity limits specification.");
532 if (limits_.has_acceleration_limits)
534 assert(period.seconds() > 0.0);
535 const double dt = period.seconds();
537 vel_low = std::max(prev_vel_ - limits_.max_acceleration * dt, -limits_.max_velocity);
538 vel_high = std::min(prev_vel_ + limits_.max_acceleration * dt, limits_.max_velocity);
542 vel_low = -limits_.max_velocity;
543 vel_high = limits_.max_velocity;
547 const double vel_cmd = rcppmath::clamp(jcmdh_.get_value(), vel_low, vel_high);
548 jcmdh_.set_value(vel_cmd);
551 prev_vel_ = jcmdh_.get_value();
565 const hardware_interface::JointHandle & jposh,
const hardware_interface::JointHandle & jvelh,
566 const hardware_interface::JointHandle & jcmdh,
567 const joint_limits_interface::JointLimits & limits,
568 const joint_limits_interface::SoftJointLimits & soft_limits)
571 if (limits.has_velocity_limits)
573 max_vel_limit_ = limits.max_velocity;
577 max_vel_limit_ = std::numeric_limits<double>::max();
589 double min_vel, max_vel;
590 if (limits_.has_position_limits)
593 const double pos = jposh_.get_value();
594 min_vel = rcppmath::clamp(
595 -soft_limits_.k_position * (pos - soft_limits_.min_position), -max_vel_limit_,
597 max_vel = rcppmath::clamp(
598 -soft_limits_.k_position * (pos - soft_limits_.max_position), -max_vel_limit_,
603 min_vel = -max_vel_limit_;
604 max_vel = max_vel_limit_;
607 if (limits_.has_acceleration_limits)
610 const double delta_t = period.seconds();
611 min_vel = std::max(vel - limits_.max_acceleration * delta_t, min_vel);
612 max_vel = std::min(vel + limits_.max_acceleration * delta_t, max_vel);
615 jcmdh_.set_value(rcppmath::clamp(jcmdh_.get_value(), min_vel, max_vel));
619 double max_vel_limit_;
Definition joint_limits_interface.hpp:329
void enforce_limits(const rclcpp::Duration &period) override
Definition joint_limits_interface.hpp:367
A handle used to enforce position, velocity and effort limits of an effort-controlled joint.
Definition joint_limits_interface.hpp:403
void enforce_limits(const rclcpp::Duration &period) override
Enforce position, velocity and effort limits for a joint subject to soft limits.
Definition joint_limits_interface.hpp:445
Definition joint_limits_interface.hpp:43
virtual void reset()
Clear stored state, causing it to reset next iteration.
Definition joint_limits_interface.hpp:91
double get_velocity(const rclcpp::Duration &period) const
Return velocity for limit calculations.
Definition joint_limits_interface.hpp:112
virtual void enforce_limits(const rclcpp::Duration &period)=0
Sub-class implementation of limit enforcing policy.
std::string get_name() const
Definition joint_limits_interface.hpp:79
An exception related to a JointLimitsInterface.
Definition joint_limits_interface_exception.hpp:24
Definition joint_limits_interface.hpp:124
Definition joint_limits_interface.hpp:150
void enforce_limits(const rclcpp::Duration &period)
Enforce position and velocity limits for a joint that is not subject to soft limits.
Definition joint_limits_interface.hpp:175
A handle used to enforce position and velocity limits of a position-controlled joint.
Definition joint_limits_interface.hpp:242
void enforce_limits(const rclcpp::Duration &period) override
Enforce position and velocity limits for a joint subject to soft limits.
Definition joint_limits_interface.hpp:266
A handle used to enforce velocity and acceleration limits of a velocity-controlled joint.
Definition joint_limits_interface.hpp:488
void enforce_limits(const rclcpp::Duration &period) override
Enforce joint velocity and acceleration limits.
Definition joint_limits_interface.hpp:526
Definition joint_limits_interface.hpp:560
void enforce_limits(const rclcpp::Duration &period)
Definition joint_limits_interface.hpp:587
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21
Definition joint_limits_interface.hpp:37