Skip to content

Commit 0f8c549

Browse files
Use std::clamp (#959)
1 parent 2fea64f commit 0f8c549

File tree

1 file changed

+20
-22
lines changed

1 file changed

+20
-22
lines changed

joint_limits_interface/include/joint_limits_interface/joint_limits_interface.hpp

Lines changed: 20 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,6 @@
1717
#ifndef JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
1818
#define JOINT_LIMITS_INTERFACE__JOINT_LIMITS_INTERFACE_HPP_
1919

20-
#include <hardware_interface/joint_handle.hpp>
21-
#include <hardware_interface/types/hardware_interface_type_values.hpp>
22-
23-
#include <rclcpp/duration.hpp>
24-
#include <rclcpp/rclcpp.hpp>
25-
26-
#include <rcppmath/clamp.hpp>
27-
2820
#include <algorithm>
2921
#include <cassert>
3022
#include <cmath>
@@ -35,6 +27,12 @@
3527
#include "joint_limits_interface/joint_limits.hpp"
3628
#include "joint_limits_interface/joint_limits_interface_exception.hpp"
3729

30+
#include <hardware_interface/joint_handle.hpp>
31+
#include <hardware_interface/types/hardware_interface_type_values.hpp>
32+
33+
#include <rclcpp/duration.hpp>
34+
#include <rclcpp/rclcpp.hpp>
35+
3836
namespace joint_limits_interface
3937
{
4038
/**
@@ -199,7 +197,7 @@ class PositionJointSaturationHandle : public JointLimitHandle
199197
}
200198

201199
// clamp command position to our computed min/max position
202-
const double cmd = rcppmath::clamp(jcmdh_.get_value(), min_pos, max_pos);
200+
const double cmd = std::clamp(jcmdh_.get_value(), min_pos, max_pos);
203201
jcmdh_.set_value(cmd);
204202

205203
prev_pos_ = cmd;
@@ -283,11 +281,11 @@ class PositionJointSoftLimitsHandle : public JointSoftLimitsHandle
283281
if (limits_.has_position_limits)
284282
{
285283
// Velocity bounds depend on the velocity limit and the proximity to the position limit
286-
soft_min_vel = rcppmath::clamp(
284+
soft_min_vel = std::clamp(
287285
-soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
288286
limits_.max_velocity);
289287

290-
soft_max_vel = rcppmath::clamp(
288+
soft_max_vel = std::clamp(
291289
-soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
292290
limits_.max_velocity);
293291
}
@@ -312,7 +310,7 @@ class PositionJointSoftLimitsHandle : public JointSoftLimitsHandle
312310
}
313311

314312
// Saturate position command according to bounds
315-
const double pos_cmd = rcppmath::clamp(jcmdh_.get_value(), pos_low, pos_high);
313+
const double pos_cmd = std::clamp(jcmdh_.get_value(), pos_low, pos_high);
316314
jcmdh_.set_value(pos_cmd);
317315

318316
// Cache variables
@@ -393,7 +391,7 @@ class EffortJointSaturationHandle : public JointLimitHandle
393391
max_eff = 0.0;
394392
}
395393

396-
double clamped = rcppmath::clamp(jcmdh_.get_value(), min_eff, max_eff);
394+
double clamped = std::clamp(jcmdh_.get_value(), min_eff, max_eff);
397395
jcmdh_.set_value(clamped);
398396
}
399397
};
@@ -456,11 +454,11 @@ class EffortJointSoftLimitsHandle : public JointSoftLimitsHandle
456454
if (limits_.has_position_limits)
457455
{
458456
// Velocity bounds depend on the velocity limit and the proximity to the position limit
459-
soft_min_vel = rcppmath::clamp(
457+
soft_min_vel = std::clamp(
460458
-soft_limits_.k_position * (pos - soft_limits_.min_position), -limits_.max_velocity,
461459
limits_.max_velocity);
462460

463-
soft_max_vel = rcppmath::clamp(
461+
soft_max_vel = std::clamp(
464462
-soft_limits_.k_position * (pos - soft_limits_.max_position), -limits_.max_velocity,
465463
limits_.max_velocity);
466464
}
@@ -472,14 +470,14 @@ class EffortJointSoftLimitsHandle : public JointSoftLimitsHandle
472470
}
473471

474472
// Effort bounds depend on the velocity and effort bounds
475-
const double soft_min_eff = rcppmath::clamp(
473+
const double soft_min_eff = std::clamp(
476474
-soft_limits_.k_velocity * (vel - soft_min_vel), -limits_.max_effort, limits_.max_effort);
477475

478-
const double soft_max_eff = rcppmath::clamp(
476+
const double soft_max_eff = std::clamp(
479477
-soft_limits_.k_velocity * (vel - soft_max_vel), -limits_.max_effort, limits_.max_effort);
480478

481479
// Saturate effort command according to bounds
482-
const double eff_cmd = rcppmath::clamp(jcmdh_.get_value(), soft_min_eff, soft_max_eff);
480+
const double eff_cmd = std::clamp(jcmdh_.get_value(), soft_min_eff, soft_max_eff);
483481
jcmdh_.set_value(eff_cmd);
484482
}
485483
};
@@ -545,7 +543,7 @@ class VelocityJointSaturationHandle : public JointLimitHandle
545543
}
546544

547545
// Saturate velocity command according to limits
548-
const double vel_cmd = rcppmath::clamp(jcmdh_.get_value(), vel_low, vel_high);
546+
const double vel_cmd = std::clamp(jcmdh_.get_value(), vel_low, vel_high);
549547
jcmdh_.set_value(vel_cmd);
550548

551549
// Cache variables
@@ -592,10 +590,10 @@ class VelocityJointSoftLimitsHandle : public JointSoftLimitsHandle
592590
{
593591
// Velocity bounds depend on the velocity limit and the proximity to the position limit.
594592
const double pos = jposh_.get_value();
595-
min_vel = rcppmath::clamp(
593+
min_vel = std::clamp(
596594
-soft_limits_.k_position * (pos - soft_limits_.min_position), -max_vel_limit_,
597595
max_vel_limit_);
598-
max_vel = rcppmath::clamp(
596+
max_vel = std::clamp(
599597
-soft_limits_.k_position * (pos - soft_limits_.max_position), -max_vel_limit_,
600598
max_vel_limit_);
601599
}
@@ -613,7 +611,7 @@ class VelocityJointSoftLimitsHandle : public JointSoftLimitsHandle
613611
max_vel = std::min(vel + limits_.max_acceleration * delta_t, max_vel);
614612
}
615613

616-
jcmdh_.set_value(rcppmath::clamp(jcmdh_.get_value(), min_vel, max_vel));
614+
jcmdh_.set_value(std::clamp(jcmdh_.get_value(), min_vel, max_vel));
617615
}
618616

619617
private:

0 commit comments

Comments
 (0)