joint_limits_interface.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 // Copyright (c) 2008, Willow Garage, Inc.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #pragma once
32 
33 
34 #include <algorithm>
35 #include <cassert>
36 #include <cmath>
37 #include <limits>
38 
39 #include <ros/duration.h>
40 
43 
46 
47 namespace joint_limits_interface
48 {
49 
50 namespace internal
51 {
52 
53 template<typename T>
54 T saturate(const T val, const T min_val, const T max_val)
55 {
56  return std::min(std::max(val, min_val), max_val);
57 }
58 
59 }
60 
64 {
65 public:
67  : jh_(jh),
68  limits_(limits)
69  {
70 
72  {
75  }
76  else
77  {
78  min_pos_limit_ = -std::numeric_limits<double>::max();
79  max_pos_limit_ = std::numeric_limits<double>::max();
80  }
81  }
82 
84  std::string getName() const {return jh_.getName();}
85 
91  void enforceLimits(const ros::Duration& period)
92  {
93  if (std::isnan(prev_cmd_))
95 
96  double min_pos, max_pos;
98  {
99  const double delta_pos = limits_.max_velocity * period.toSec();
100  min_pos = std::max(prev_cmd_ - delta_pos, min_pos_limit_);
101  max_pos = std::min(prev_cmd_ + delta_pos, max_pos_limit_);
102  }
103  else
104  {
105  min_pos = min_pos_limit_;
106  max_pos = max_pos_limit_;
107  }
108 
109  const double cmd = internal::saturate(jh_.getCommand(), min_pos, max_pos);
110  jh_.setCommand(cmd);
111  prev_cmd_ = cmd;
112  }
113 
117  void reset(){
118  prev_cmd_ = std::numeric_limits<double>::quiet_NaN();
119  }
120 
121 private:
125 
126  double prev_cmd_ = {std::numeric_limits<double>::quiet_NaN()};
127 };
128 
159 // TODO: Leverage %Reflexxes Type II library for acceleration limits handling?
161 {
162 public:
163  PositionJointSoftLimitsHandle() = default;
164 
166  const JointLimits& limits,
167  const SoftJointLimits& soft_limits)
168  : jh_(jh),
169  limits_(limits),
170  soft_limits_(soft_limits)
171  {
172  if (!limits.has_velocity_limits)
173  {
174  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
175  "'. It has no velocity limits specification.");
176  }
177  }
178 
180  std::string getName() const {return jh_.getName();}
181 
188  void enforceLimits(const ros::Duration& period)
189  {
190  assert(period.toSec() > 0.0);
191 
192  using internal::saturate;
193 
194  // Current position
195  // TODO: Doc!
196  if (std::isnan(prev_cmd_)) {prev_cmd_ = jh_.getPosition();} // Happens only once at initialization
197  const double pos = prev_cmd_;
198 
199  // Velocity bounds
200  double soft_min_vel;
201  double soft_max_vel;
202 
204  {
205  // Velocity bounds depend on the velocity limit and the proximity to the position limit
206  soft_min_vel = saturate(-soft_limits_.k_position * (pos - soft_limits_.min_position),
209 
210  soft_max_vel = saturate(-soft_limits_.k_position * (pos - soft_limits_.max_position),
213  }
214  else
215  {
216  // No position limits, eg. continuous joints
217  soft_min_vel = -limits_.max_velocity;
218  soft_max_vel = limits_.max_velocity;
219  }
220 
221  // Position bounds
222  const double dt = period.toSec();
223  double pos_low = pos + soft_min_vel * dt;
224  double pos_high = pos + soft_max_vel * dt;
225 
227  {
228  // This extra measure safeguards against pathological cases, like when the soft limit lies beyond the hard limit
229  pos_low = std::max(pos_low, limits_.min_position);
230  pos_high = std::min(pos_high, limits_.max_position);
231  }
232 
233  // Saturate position command according to bounds
234  const double pos_cmd = saturate(jh_.getCommand(),
235  pos_low,
236  pos_high);
237  jh_.setCommand(pos_cmd);
238 
239  // Cache variables
241  }
242 
246  void reset(){
247  prev_cmd_ = std::numeric_limits<double>::quiet_NaN();
248  }
249 
250 private:
254 
255  double prev_cmd_ = {std::numeric_limits<double>::quiet_NaN()};
256 };
257 
261 {
262 public:
264  : jh_(jh)
265  , limits_(limits)
266  {
267  if (!limits.has_velocity_limits)
268  {
269  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
270  "'. It has no velocity limits specification.");
271  }
272  if (!limits.has_effort_limits)
273  {
274  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
275  "'. It has no efforts limits specification.");
276  }
277  }
278 
280  std::string getName() const {return jh_.getName();}
281 
285  void enforceLimits(const ros::Duration& /* period */)
286  {
287  double min_eff = -limits_.max_effort;
288  double max_eff = limits_.max_effort;
289 
291  {
292  const double pos = jh_.getPosition();
293  if (pos < limits_.min_position)
294  min_eff = 0.0;
295  else if (pos > limits_.max_position)
296  max_eff = 0.0;
297  }
298 
299  const double vel = jh_.getVelocity();
300  if (vel < -limits_.max_velocity)
301  min_eff = 0.0;
302  else if (vel > limits_.max_velocity)
303  max_eff = 0.0;
304 
305  jh_.setCommand(internal::saturate(jh_.getCommand(), min_eff, max_eff));
306  }
307 
308 private:
311 };
312 
315 // TODO: This class is untested!. Update unit tests accordingly.
317 {
318 public:
319  EffortJointSoftLimitsHandle() = default;
320 
322  const JointLimits& limits,
323  const SoftJointLimits& soft_limits)
324  : jh_(jh),
325  limits_(limits),
326  soft_limits_(soft_limits)
327  {
328  if (!limits.has_velocity_limits)
329  {
330  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
331  "'. It has no velocity limits specification.");
332  }
333  if (!limits.has_effort_limits)
334  {
335  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
336  "'. It has no effort limits specification.");
337  }
338  }
339 
341  std::string getName() const {return jh_.getName();}
342 
348  void enforceLimits(const ros::Duration& /*period*/)
349  {
350  using internal::saturate;
351 
352  // Current state
353  const double pos = jh_.getPosition();
354  const double vel = jh_.getVelocity();
355 
356  // Velocity bounds
357  double soft_min_vel;
358  double soft_max_vel;
359 
361  {
362  // Velocity bounds depend on the velocity limit and the proximity to the position limit
363  soft_min_vel = saturate(-soft_limits_.k_position * (pos - soft_limits_.min_position),
366 
367  soft_max_vel = saturate(-soft_limits_.k_position * (pos - soft_limits_.max_position),
370  }
371  else
372  {
373  // No position limits, eg. continuous joints
374  soft_min_vel = -limits_.max_velocity;
375  soft_max_vel = limits_.max_velocity;
376  }
377 
378  // Effort bounds depend on the velocity and effort bounds
379  const double soft_min_eff = saturate(-soft_limits_.k_velocity * (vel - soft_min_vel),
382 
383  const double soft_max_eff = saturate(-soft_limits_.k_velocity * (vel - soft_max_vel),
386 
387  // Saturate effort command according to bounds
388  const double eff_cmd = saturate(jh_.getCommand(),
389  soft_min_eff,
390  soft_max_eff);
391  jh_.setCommand(eff_cmd);
392  }
393 
394 private:
398 };
399 
400 
403 {
404 public:
405  VelocityJointSaturationHandle() = default;
406 
408  : jh_(jh)
409  , limits_(limits)
410  {
411  if (!limits.has_velocity_limits)
412  {
413  throw JointLimitsInterfaceException("Cannot enforce limits for joint '" + getName() +
414  "'. It has no velocity limits specification.");
415  }
416  }
417 
419  std::string getName() const {return jh_.getName();}
420 
425  void enforceLimits(const ros::Duration& period)
426  {
427  using internal::saturate;
428 
429  // Velocity bounds
430  double vel_low;
431  double vel_high;
432 
434  {
435  assert(period.toSec() > 0.0);
436  const double dt = period.toSec();
437 
438  vel_low = std::max(prev_cmd_ - limits_.max_acceleration * dt, -limits_.max_velocity);
439  vel_high = std::min(prev_cmd_ + limits_.max_acceleration * dt, limits_.max_velocity);
440  }
441  else
442  {
443  vel_low = -limits_.max_velocity;
444  vel_high = limits_.max_velocity;
445  }
446 
447  // Saturate velocity command according to limits
448  const double vel_cmd = saturate(jh_.getCommand(),
449  vel_low,
450  vel_high);
451  jh_.setCommand(vel_cmd);
452 
453  // Cache variables
455  }
456 
457 private:
460 
461  double prev_cmd_ = {0.0};
462 };
463 
466 {
467 public:
469  const SoftJointLimits& soft_limits)
470  : jh_(jh)
471  , limits_(limits)
472  , soft_limits_(soft_limits)
473  {
474  if (limits.has_velocity_limits)
475  max_vel_limit_ = limits.max_velocity;
476  else
477  max_vel_limit_ = std::numeric_limits<double>::max();
478  }
479 
481  std::string getName() const {return jh_.getName();}
482 
488  void enforceLimits(const ros::Duration& period)
489  {
490  using internal::saturate;
491 
492  double min_vel, max_vel;
494  {
495  // Velocity bounds depend on the velocity limit and the proximity to the position limit.
496  const double pos = jh_.getPosition();
501  }
502  else
503  {
504  min_vel = -max_vel_limit_;
505  max_vel = max_vel_limit_;
506  }
507 
509  {
510  const double vel = jh_.getVelocity();
511  const double delta_t = period.toSec();
512  min_vel = std::max(vel - limits_.max_acceleration * delta_t, min_vel);
513  max_vel = std::min(vel + limits_.max_acceleration * delta_t, max_vel);
514  }
515 
516  jh_.setCommand(saturate(jh_.getCommand(), min_vel, max_vel));
517  }
518 
519 private:
524 };
525 
535 template <class HandleType>
537 {
538 public:
539  HandleType getHandle(const std::string& name)
540  {
541  // Rethrow exception with a meaningful type
542  try
543  {
545  }
546  catch(const std::logic_error& e)
547  {
548  throw JointLimitsInterfaceException(e.what());
549  }
550  }
551 
555  void enforceLimits(const ros::Duration& period)
556  {
557  for (auto&& resource_name_and_handle : this->resource_map_)
558  {
559  resource_name_and_handle.second.enforceLimits(period);
560  }
561  }
562  /*\}*/
563 };
564 
566 class PositionJointSaturationInterface : public JointLimitsInterface<PositionJointSaturationHandle> {
567 public:
571  void reset()
572  {
573  for (auto&& resource_name_and_handle : this->resource_map_)
574  {
575  resource_name_and_handle.second.reset();
576  }
577  }
578  /*\}*/
579 };
580 
582 class PositionJointSoftLimitsInterface : public JointLimitsInterface<PositionJointSoftLimitsHandle> {
583 public:
587  void reset()
588  {
589  for (auto&& resource_name_and_handle : this->resource_map_)
590  {
591  resource_name_and_handle.second.reset();
592  }
593  }
594  /*\}*/
595 };
596 
598 class EffortJointSaturationInterface : public JointLimitsInterface<EffortJointSaturationHandle> {};
599 
601 class EffortJointSoftLimitsInterface : public JointLimitsInterface<EffortJointSoftLimitsHandle> {};
602 
604 class VelocityJointSaturationInterface : public JointLimitsInterface<VelocityJointSaturationHandle> {};
605 
607 class VelocityJointSoftLimitsInterface : public JointLimitsInterface<VelocityJointSoftLimitsHandle> {};
608 
609 }
joint_limits_interface::VelocityJointSoftLimitsHandle::enforceLimits
void enforceLimits(const ros::Duration &period)
Enforce position, velocity, and acceleration limits for a velocity-controlled joint subject to soft l...
Definition: joint_limits_interface.h:488
joint_limits_interface::PositionJointSoftLimitsHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:252
joint_limits_interface::VelocityJointSoftLimitsHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:481
joint_limits_interface::JointLimits::max_velocity
double max_velocity
Definition: joint_limits.h:40
joint_limits_interface::VelocityJointSoftLimitsHandle::soft_limits_
SoftJointLimits soft_limits_
Definition: joint_limits_interface.h:522
joint_limits_interface_exception.h
joint_limits_interface::EffortJointSoftLimitsHandle
A handle used to enforce position, velocity and effort limits of an effort-controlled joint.
Definition: joint_limits_interface.h:316
joint_limits_interface::VelocityJointSaturationHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:459
joint_limits_interface::JointLimits
Definition: joint_limits.h:36
joint_limits_interface::PositionJointSoftLimitsHandle::reset
void reset()
Reset state, in case of mode switch or e-stop.
Definition: joint_limits_interface.h:246
joint_limits_interface::SoftJointLimits::min_position
double min_position
Definition: joint_limits.h:55
joint_limits_interface::SoftJointLimits::max_position
double max_position
Definition: joint_limits.h:56
joint_limits_interface::EffortJointSoftLimitsHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:396
joint_limits_interface::PositionJointSaturationHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:123
joint_limits_interface
Definition: joint_limits.h:33
joint_limits_interface::VelocityJointSaturationInterface
Definition: joint_limits_interface.h:604
joint_limits_interface::PositionJointSoftLimitsInterface::reset
void reset()
Reset all managed handles.
Definition: joint_limits_interface.h:587
joint_limits_interface::EffortJointSaturationHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:280
joint_limits_interface::PositionJointSoftLimitsHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:180
joint_limits_interface::VelocityJointSaturationHandle::prev_cmd_
double prev_cmd_
Definition: joint_limits_interface.h:461
joint_limits_interface::VelocityJointSaturationHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:458
joint_limits_interface::JointLimits::max_position
double max_position
Definition: joint_limits.h:39
joint_limits_interface::VelocityJointSoftLimitsInterface
Definition: joint_limits_interface.h:607
joint_limits_interface::PositionJointSaturationInterface::reset
void reset()
Reset all managed handles.
Definition: joint_limits_interface.h:571
joint_limits_interface::VelocityJointSoftLimitsHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:521
joint_limits_interface::EffortJointSoftLimitsHandle::soft_limits_
SoftJointLimits soft_limits_
Definition: joint_limits_interface.h:397
joint_limits_interface::JointLimitsInterfaceException
An exception related to a JointLimitsInterface.
Definition: joint_limits_interface_exception.h:38
joint_limits_interface::PositionJointSoftLimitsHandle::enforceLimits
void enforceLimits(const ros::Duration &period)
Enforce position and velocity limits for a joint subject to soft limits.
Definition: joint_limits_interface.h:188
joint_limits_interface::EffortJointSaturationHandle::EffortJointSaturationHandle
EffortJointSaturationHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits)
Definition: joint_limits_interface.h:263
joint_limits_interface::SoftJointLimits::k_position
double k_position
Definition: joint_limits.h:57
hardware_interface::JointHandle::setCommand
void setCommand(double command)
joint_limits_interface::PositionJointSaturationInterface
Definition: joint_limits_interface.h:566
joint_limits_interface::PositionJointSaturationHandle::PositionJointSaturationHandle
PositionJointSaturationHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits)
Definition: joint_limits_interface.h:66
joint_limits_interface::EffortJointSoftLimitsHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:395
joint_limits_interface::PositionJointSoftLimitsHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:251
joint_limits_interface::PositionJointSoftLimitsHandle
A handle used to enforce position and velocity limits of a position-controlled joint.
Definition: joint_limits_interface.h:160
joint_limits_interface::PositionJointSaturationHandle
A handle used to enforce position and velocity limits of a position-controlled joint that does not ha...
Definition: joint_limits_interface.h:63
joint_limits_interface::PositionJointSaturationHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:84
joint_limits_interface::SoftJointLimits::k_velocity
double k_velocity
Definition: joint_limits.h:58
joint_limits_interface::JointLimits::max_effort
double max_effort
Definition: joint_limits.h:43
joint_limits_interface::EffortJointSoftLimitsHandle::EffortJointSoftLimitsHandle
EffortJointSoftLimitsHandle()=default
joint_limits_interface::EffortJointSoftLimitsInterface
Definition: joint_limits_interface.h:601
duration.h
joint_limits_interface::VelocityJointSaturationHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:419
joint_limits_interface::EffortJointSoftLimitsHandle::enforceLimits
void enforceLimits(const ros::Duration &)
Enforce position, velocity and effort limits for a joint subject to soft limits.
Definition: joint_limits_interface.h:348
joint_command_interface.h
joint_limits_interface::EffortJointSoftLimitsHandle::getName
std::string getName() const
Definition: joint_limits_interface.h:341
hardware_interface::JointHandle::getCommand
double getCommand() const
joint_limits_interface::VelocityJointSaturationHandle
A handle used to enforce velocity and acceleration limits of a velocity-controlled joint.
Definition: joint_limits_interface.h:402
joint_limits_interface::VelocityJointSoftLimitsHandle::max_vel_limit_
double max_vel_limit_
Definition: joint_limits_interface.h:523
joint_limits_interface::VelocityJointSaturationHandle::enforceLimits
void enforceLimits(const ros::Duration &period)
Enforce joint velocity and acceleration limits.
Definition: joint_limits_interface.h:425
joint_limits_interface::PositionJointSaturationHandle::reset
void reset()
Reset state, in case of mode switch or e-stop.
Definition: joint_limits_interface.h:117
joint_limits_interface::JointLimitsInterface::enforceLimits
void enforceLimits(const ros::Duration &period)
Enforce limits for all managed handles.
Definition: joint_limits_interface.h:555
joint_limits_interface::PositionJointSaturationHandle::prev_cmd_
double prev_cmd_
Definition: joint_limits_interface.h:126
joint_limits_interface::VelocityJointSoftLimitsHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:520
hardware_interface::JointStateHandle::getName
std::string getName() const
joint_limits_interface::PositionJointSaturationHandle::min_pos_limit_
double min_pos_limit_
Definition: joint_limits_interface.h:124
joint_limits_interface::PositionJointSaturationHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:122
joint_limits_interface::VelocityJointSoftLimitsHandle::VelocityJointSoftLimitsHandle
VelocityJointSoftLimitsHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits, const SoftJointLimits &soft_limits)
Definition: joint_limits_interface.h:468
joint_limits.h
joint_limits_interface::VelocityJointSoftLimitsHandle
A handle used to enforce position, velocity, and acceleration limits of a velocity-controlled joint.
Definition: joint_limits_interface.h:465
hardware_interface::ResourceManager
hardware_interface::ResourceManager::getHandle
ResourceHandle getHandle(const std::string &name)
joint_limits_interface::JointLimits::has_velocity_limits
bool has_velocity_limits
Definition: joint_limits.h:46
hardware_interface::JointHandle
hardware_interface::JointStateHandle::getVelocity
double getVelocity() const
joint_limits_interface::JointLimits::min_position
double min_position
Definition: joint_limits.h:38
joint_limits_interface::internal::saturate
T saturate(const T val, const T min_val, const T max_val)
Definition: joint_limits_interface.h:54
hardware_interface::JointStateHandle::getPosition
double getPosition() const
joint_limits_interface::EffortJointSaturationHandle::jh_
hardware_interface::JointHandle jh_
Definition: joint_limits_interface.h:309
joint_limits_interface::PositionJointSoftLimitsInterface
Definition: joint_limits_interface.h:582
joint_limits_interface::JointLimits::has_acceleration_limits
bool has_acceleration_limits
Definition: joint_limits.h:47
joint_limits_interface::EffortJointSoftLimitsHandle::EffortJointSoftLimitsHandle
EffortJointSoftLimitsHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits, const SoftJointLimits &soft_limits)
Definition: joint_limits_interface.h:321
joint_limits_interface::JointLimits::max_acceleration
double max_acceleration
Definition: joint_limits.h:41
joint_limits_interface::PositionJointSoftLimitsHandle::soft_limits_
SoftJointLimits soft_limits_
Definition: joint_limits_interface.h:253
joint_limits_interface::PositionJointSaturationHandle::max_pos_limit_
double max_pos_limit_
Definition: joint_limits_interface.h:124
resource_manager.h
joint_limits_interface::PositionJointSaturationHandle::enforceLimits
void enforceLimits(const ros::Duration &period)
Enforce position and velocity limits for a joint that is not subject to soft limits.
Definition: joint_limits_interface.h:91
joint_limits_interface::JointLimitsInterface::getHandle
HandleType getHandle(const std::string &name)
Definition: joint_limits_interface.h:539
DurationBase< Duration >::toSec
double toSec() const
joint_limits_interface::PositionJointSoftLimitsHandle::prev_cmd_
double prev_cmd_
Definition: joint_limits_interface.h:255
joint_limits_interface::VelocityJointSaturationHandle::VelocityJointSaturationHandle
VelocityJointSaturationHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits)
Definition: joint_limits_interface.h:407
joint_limits_interface::EffortJointSaturationHandle
A handle used to enforce position, velocity, and effort limits of an effort-controlled joint that doe...
Definition: joint_limits_interface.h:260
cmd
string cmd
joint_limits_interface::SoftJointLimits
Definition: joint_limits.h:53
joint_limits_interface::EffortJointSaturationHandle::enforceLimits
void enforceLimits(const ros::Duration &)
Enforce position, velocity, and effort limits for a joint that is not subject to soft limits.
Definition: joint_limits_interface.h:285
hardware_interface::ResourceManager< HandleType >::resource_map_
ResourceMap resource_map_
joint_limits_interface::JointLimitsInterface
Interface for enforcing joint limits.
Definition: joint_limits_interface.h:536
ros::Duration
joint_limits_interface::PositionJointSoftLimitsHandle::PositionJointSoftLimitsHandle
PositionJointSoftLimitsHandle()=default
joint_limits_interface::JointLimits::has_position_limits
bool has_position_limits
Definition: joint_limits.h:45
joint_limits_interface::PositionJointSoftLimitsHandle::PositionJointSoftLimitsHandle
PositionJointSoftLimitsHandle(const hardware_interface::JointHandle &jh, const JointLimits &limits, const SoftJointLimits &soft_limits)
Definition: joint_limits_interface.h:165
joint_limits_interface::JointLimits::has_effort_limits
bool has_effort_limits
Definition: joint_limits.h:49
joint_limits_interface::EffortJointSaturationInterface
Definition: joint_limits_interface.h:598
joint_limits_interface::EffortJointSaturationHandle::limits_
JointLimits limits_
Definition: joint_limits_interface.h:310
joint_limits_interface::VelocityJointSaturationHandle::VelocityJointSaturationHandle
VelocityJointSaturationHandle()=default


joint_limits_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:08:07