ros2_control - humble
Loading...
Searching...
No Matches
joint_limits_interface.hpp
1// Copyright 2020 PAL Robotics S.L.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
16
17#ifndef JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
18#define JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
19
20#include <algorithm>
21#include <cassert>
22#include <cmath>
23#include <limits>
24#include <memory>
25#include <string>
26
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>
32
33#include "joint_limits_interface/joint_limits.hpp"
34#include "joint_limits_interface/joint_limits_interface_exception.hpp"
35
37{
43{
44public:
46 : prev_pos_(std::numeric_limits<double>::quiet_NaN()),
47 prev_vel_(0.0),
50 jcmdh_("position_command")
51 {
52 }
53
55 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jcmdh,
56 const JointLimits & limits)
57 : jposh_(jposh),
59 jcmdh_(jcmdh),
60 limits_(limits),
61 prev_pos_(std::numeric_limits<double>::quiet_NaN()),
62 prev_vel_(0.0)
63 {
64 }
65
67 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jvelh,
68 const hardware_interface::JointHandle & jcmdh, const JointLimits & limits)
69 : jposh_(jposh),
70 jvelh_(jvelh),
71 jcmdh_(jcmdh),
72 limits_(limits),
73 prev_pos_(std::numeric_limits<double>::quiet_NaN()),
74 prev_vel_(0.0)
75 {
76 }
77
79 std::string get_name() const
80 {
81 return jposh_ ? jposh_.get_name()
82 : jvelh_ ? jvelh_.get_name()
83 : jcmdh_ ? jcmdh_.get_name()
84 : std::string();
85 }
86
88 virtual void enforce_limits(const rclcpp::Duration & period) = 0;
89
91 virtual void reset()
92 {
93 prev_pos_ = std::numeric_limits<double>::quiet_NaN();
94 prev_vel_ = 0.0;
95 }
96
97protected:
98 hardware_interface::JointHandle jposh_;
99 hardware_interface::JointHandle jvelh_;
100 hardware_interface::JointHandle jcmdh_;
101 joint_limits_interface::JointLimits limits_;
102
103 // stored state - track position and velocity of last update
104 double prev_pos_;
105 double prev_vel_;
106
108
112 double get_velocity(const rclcpp::Duration & period) const
113 {
114 // if we have a handle to a velocity state we can directly return state velocity
115 // otherwise we will estimate velocity from previous position (command or state)
116 return jvelh_ ? jvelh_.get_value() : (jposh_.get_value() - prev_pos_) / period.seconds();
117 }
118};
119
124{
125public:
127
129 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jcmdh,
130 const JointLimits & limits, const SoftJointLimits & soft_limits)
131 : JointLimitHandle(jposh, jcmdh, limits), soft_limits_(soft_limits)
132 {
133 }
134
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)
139 : JointLimitHandle(jposh, jvelh, jcmdh, limits), soft_limits_(soft_limits)
140 {
141 }
142
143protected:
144 joint_limits_interface::SoftJointLimits soft_limits_;
145};
146
150{
151public:
153
155 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jcmdh,
156 const JointLimits & limits)
157 : JointLimitHandle(jposh, jcmdh, limits)
158 {
159 if (limits_.has_position_limits)
160 {
161 min_pos_limit_ = limits_.min_position;
162 max_pos_limit_ = limits_.max_position;
163 }
164 else
165 {
166 min_pos_limit_ = -std::numeric_limits<double>::max();
167 max_pos_limit_ = std::numeric_limits<double>::max();
168 }
169 }
170
172
175 void enforce_limits(const rclcpp::Duration & period)
176 {
177 if (std::isnan(prev_pos_))
178 {
179 prev_pos_ = jposh_.get_value();
180 }
181
182 double min_pos, max_pos;
183 if (limits_.has_velocity_limits)
184 {
185 // enforce velocity limits
186 // set constraints on where the position can be based on the
187 // max velocity times seconds since last update
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_);
191 }
192 else
193 {
194 // no velocity limit, so position is simply limited to set extents (our imposed soft limits)
195 min_pos = min_pos_limit_;
196 max_pos = max_pos_limit_;
197 }
198
199 // clamp command position to our computed min/max position
200 const double cmd = rcppmath::clamp(jcmdh_.get_value(), min_pos, max_pos);
201 jcmdh_.set_value(cmd);
202
203 prev_pos_ = cmd;
204 }
205
206private:
207 double min_pos_limit_, max_pos_limit_;
208};
209
211
240// TODO(anyone): Leverage %Reflexxes Type II library for acceleration limits handling?
242{
243public:
245
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)
250 : JointSoftLimitsHandle(jposh, jcmdh, limits, soft_limits)
251 {
252 if (!limits.has_velocity_limits)
253 {
255 "Cannot enforce limits for joint '" + get_name() +
256 "'. It has no velocity limits specification.");
257 }
258 }
259
261
266 void enforce_limits(const rclcpp::Duration & period) override
267 {
268 assert(period.seconds() > 0.0);
269
270 // Current position
271 if (std::isnan(prev_pos_))
272 {
273 // Happens only once at initialization
274 prev_pos_ = jposh_.get_value();
275 }
276 const double pos = prev_pos_;
277
278 // Velocity bounds
279 double soft_min_vel;
280 double soft_max_vel;
281
282 if (limits_.has_position_limits)
283 {
284 // Velocity bounds depend on the velocity limit and the proximity to the position limit
285 soft_min_vel = rcppmath::clamp(
286 -soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
287 limits_.max_velocity);
288
289 soft_max_vel = rcppmath::clamp(
290 -soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
291 limits_.max_velocity);
292 }
293 else
294 {
295 // No position limits, eg. continuous joints
296 soft_min_vel = -limits_.max_velocity;
297 soft_max_vel = limits_.max_velocity;
298 }
299
300 // Position bounds
301 const double dt = period.seconds();
302 double pos_low = pos + soft_min_vel * dt;
303 double pos_high = pos + soft_max_vel * dt;
304
305 if (limits_.has_position_limits)
306 {
307 // This extra measure safeguards against pathological cases, like when the soft limit lies
308 // beyond the hard limit
309 pos_low = std::max(pos_low, limits_.min_position);
310 pos_high = std::min(pos_high, limits_.max_position);
311 }
312
313 // Saturate position command according to bounds
314 const double pos_cmd = rcppmath::clamp(jcmdh_.get_value(), pos_low, pos_high);
315 jcmdh_.set_value(pos_cmd);
316
317 // Cache variables
318 // todo: shouldn't this just be pos_cmd? why call into the command handle to
319 // get what we have in the above line?
320 prev_pos_ = jcmdh_.get_value();
321 }
322};
323
329{
330public:
332
334 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jvelh,
335 const hardware_interface::JointHandle & jcmdh,
336 const joint_limits_interface::JointLimits & limits)
337 : JointLimitHandle(jposh, jvelh, jcmdh, limits)
338 {
339 if (!limits.has_velocity_limits)
340 {
342 "Cannot enforce limits for joint '" + get_name() +
343 "'. It has no velocity limits specification.");
344 }
345 if (!limits.has_effort_limits)
346 {
348 "Cannot enforce limits for joint '" + get_name() +
349 "'. It has no efforts limits specification.");
350 }
351 }
352
354 const hardware_interface::JointHandle & jposh, const hardware_interface::JointHandle & jcmdh,
355 const joint_limits_interface::JointLimits & limits)
357 jposh, hardware_interface::JointHandle(hardware_interface::HW_IF_VELOCITY), jcmdh, limits)
358 {
359 }
360
367 void enforce_limits(const rclcpp::Duration & period) override
368 {
369 double min_eff = -limits_.max_effort;
370 double max_eff = limits_.max_effort;
371
372 if (limits_.has_position_limits)
373 {
374 const double pos = jposh_.get_value();
375 if (pos < limits_.min_position)
376 {
377 min_eff = 0.0;
378 }
379 else if (pos > limits_.max_position)
380 {
381 max_eff = 0.0;
382 }
383 }
384
385 const double vel = get_velocity(period);
386 if (vel < -limits_.max_velocity)
387 {
388 min_eff = 0.0;
389 }
390 else if (vel > limits_.max_velocity)
391 {
392 max_eff = 0.0;
393 }
394
395 double clamped = rcppmath::clamp(jcmdh_.get_value(), min_eff, max_eff);
396 jcmdh_.set_value(clamped);
397 }
398};
399
401// TODO(anyone): This class is untested!. Update unit tests accordingly.
403{
404public:
406
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)
412 : JointSoftLimitsHandle(jposh, jvelh, jcmdh, limits, soft_limits)
413 {
414 if (!limits.has_velocity_limits)
415 {
417 "Cannot enforce limits for joint '" + get_name() +
418 "'. It has no velocity limits specification.");
419 }
420 if (!limits.has_effort_limits)
421 {
423 "Cannot enforce limits for joint '" + get_name() +
424 "'. It has no effort limits specification.");
425 }
426 }
427
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)
433 jposh, hardware_interface::JointHandle(hardware_interface::HW_IF_VELOCITY), jcmdh, limits,
434 soft_limits)
435 {
436 }
437
439
445 void enforce_limits(const rclcpp::Duration & period) override
446 {
447 // Current state
448 const double pos = jposh_.get_value();
449 const double vel = get_velocity(period);
450
451 // Velocity bounds
452 double soft_min_vel;
453 double soft_max_vel;
454
455 if (limits_.has_position_limits)
456 {
457 // Velocity bounds depend on the velocity limit and the proximity to the position limit
458 soft_min_vel = rcppmath::clamp(
459 -soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
460 limits_.max_velocity);
461
462 soft_max_vel = rcppmath::clamp(
463 -soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
464 limits_.max_velocity);
465 }
466 else
467 {
468 // No position limits, eg. continuous joints
469 soft_min_vel = -limits_.max_velocity;
470 soft_max_vel = limits_.max_velocity;
471 }
472
473 // Effort bounds depend on the velocity and effort bounds
474 const double soft_min_eff = rcppmath::clamp(
475 -soft_limits_.k_velocity * (vel - soft_min_vel), -limits_.max_effort, limits_.max_effort);
476
477 const double soft_max_eff = rcppmath::clamp(
478 -soft_limits_.k_velocity * (vel - soft_max_vel), -limits_.max_effort, limits_.max_effort);
479
480 // Saturate effort command according to bounds
481 const double eff_cmd = rcppmath::clamp(jcmdh_.get_value(), soft_min_eff, soft_max_eff);
482 jcmdh_.set_value(eff_cmd);
483 }
484};
485
488{
489public:
491
493 const hardware_interface::JointHandle & jvelh, // currently unused
494 const hardware_interface::JointHandle & jcmdh,
495 const joint_limits_interface::JointLimits & limits)
497 hardware_interface::JointHandle(hardware_interface::HW_IF_POSITION), jvelh, jcmdh, limits)
498 {
499 if (!limits.has_velocity_limits)
500 {
502 "Cannot enforce limits for joint '" + get_name() +
503 "'. It has no velocity limits specification.");
504 }
505 }
506
508 const hardware_interface::JointHandle & jcmdh,
509 const joint_limits_interface::JointLimits & limits)
511 hardware_interface::JointHandle(hardware_interface::HW_IF_POSITION),
512 hardware_interface::JointHandle(hardware_interface::HW_IF_VELOCITY), jcmdh, limits)
513 {
514 if (!limits.has_velocity_limits)
515 {
517 "Cannot enforce limits for joint '" + get_name() +
518 "'. It has no velocity limits specification.");
519 }
520 }
521
523
526 void enforce_limits(const rclcpp::Duration & period) override
527 {
528 // Velocity bounds
529 double vel_low;
530 double vel_high;
531
532 if (limits_.has_acceleration_limits)
533 {
534 assert(period.seconds() > 0.0);
535 const double dt = period.seconds();
536
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);
539 }
540 else
541 {
542 vel_low = -limits_.max_velocity;
543 vel_high = limits_.max_velocity;
544 }
545
546 // Saturate velocity command according to limits
547 const double vel_cmd = rcppmath::clamp(jcmdh_.get_value(), vel_low, vel_high);
548 jcmdh_.set_value(vel_cmd);
549
550 // Cache variables
551 prev_vel_ = jcmdh_.get_value();
552 }
553};
554
560{
561public:
563
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)
569 : JointSoftLimitsHandle(jposh, jvelh, jcmdh, limits, soft_limits)
570 {
571 if (limits.has_velocity_limits)
572 {
573 max_vel_limit_ = limits.max_velocity;
574 }
575 else
576 {
577 max_vel_limit_ = std::numeric_limits<double>::max();
578 }
579 }
580
587 void enforce_limits(const rclcpp::Duration & period)
588 {
589 double min_vel, max_vel;
590 if (limits_.has_position_limits)
591 {
592 // Velocity bounds depend on the velocity limit and the proximity to the position limit.
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_,
596 max_vel_limit_);
597 max_vel = rcppmath::clamp(
598 -soft_limits_.k_position * (pos - soft_limits_.max_position), -max_vel_limit_,
599 max_vel_limit_);
600 }
601 else
602 {
603 min_vel = -max_vel_limit_;
604 max_vel = max_vel_limit_;
605 }
606
607 if (limits_.has_acceleration_limits)
608 {
609 const double vel = get_velocity(period);
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);
613 }
614
615 jcmdh_.set_value(rcppmath::clamp(jcmdh_.get_value(), min_vel, max_vel));
616 }
617
618private:
619 double max_vel_limit_;
620};
621
622// TODO(anyone): Port this to ROS 2
623// //**
624// * Interface for enforcing joint limits.
625// *
626// * \tparam HandleType %Handle type. Must implement the following methods:
627// * \code
628// * void enforce_limits();
629// * std::string get_name() const;
630// * \endcode
631// */
632// template<class HandleType>
633// class joint_limits_interface::JointLimitsInterface
634// : public hardware_interface::ResourceManager<HandleType>
635// {
636// public:
637// HandleType getHandle(const std::string & name)
638// {
639// // Rethrow exception with a meaningful type
640// try {
641// return this->hardware_interface::ResourceManager<HandleType>::getHandle(name);
642// } catch (const std::logic_error & e) {
643// throw joint_limits_interface::JointLimitsInterfaceException(e.what());
644// }
645// }
646//
647// /** \name Real-Time Safe Functions
648// *\{*/
649// /** Enforce limits for all managed handles. */
650// void enforce_limits(const rclcpp::Duration & period)
651// {
652// for (auto && resource_name_and_handle : this->resource_map_) {
653// resource_name_and_handle.second.enforce_limits(period);
654// }
655// }
656// /*\}*/
657// };
658//
659// /** Interface for enforcing limits on a position-controlled joint through saturation. */
660// class PositionJointSaturationInterface
661// : public joint_limits_interface::JointLimitsInterface<PositionJointSaturationHandle>
662// {
663// public:
664// /** \name Real-Time Safe Functions
665// *\{*/
666// /** Reset all managed handles. */
667// void reset()
668// {
669// for (auto && resource_name_and_handle : this->resource_map_) {
670// resource_name_and_handle.second.reset();
671// }
672// }
673// /*\}*/
674// };
675//
676// /** Interface for enforcing limits on a position-controlled joint with soft position limits. */
677// class PositionJointSoftLimitsInterface
678// : public joint_limits_interface::JointLimitsInterface<PositionJointSoftLimitsHandle>
679// {
680// public:
681// /** \name Real-Time Safe Functions
682// *\{*/
683// /** Reset all managed handles. */
684// void reset()
685// {
686// for (auto && resource_name_and_handle : this->resource_map_) {
687// resource_name_and_handle.second.reset();
688// }
689// }
690// /*\}*/
691// };
692//
693// /** Interface for enforcing limits on an effort-controlled joint through saturation. */
694// class EffortJointSaturationInterface
695// : public joint_limits_interface::JointLimitsInterface<EffortJointSaturationHandle>
696// {
697// };
698//
699// /** Interface for enforcing limits on an effort-controlled joint with soft position limits. */
700// class EffortJointSoftLimitsInterface
701// : public joint_limits_interface::JointLimitsInterface<EffortJointSoftLimitsHandle>
702// {
703// };
704//
705// /** Interface for enforcing limits on a velocity-controlled joint through saturation. */
706// class VelocityJointSaturationInterface
707// : public joint_limits_interface::JointLimitsInterface<VelocityJointSaturationHandle>
708// {
709// };
710//
711// /** Interface for enforcing limits on a velocity-controlled joint with soft position limits. */
712// class VelocityJointSoftLimitsInterface
713// : public joint_limits_interface::JointLimitsInterface<VelocityJointSoftLimitsHandle>
714// {
715// };
716} // namespace joint_limits_interface
717
718#endif // JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
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