libfranka 0.18.0
FCI C++ API
Loading...
Searching...
No Matches
rate_limiting.h
Go to the documentation of this file.
1// Copyright (c) 2023 Franka Robotics GmbH
2// Use of this source code is governed by the Apache-2.0 license, see LICENSE
3#pragma once
4
5#include <algorithm>
6#include <array>
7#include <cmath>
8#include <limits>
9
16namespace franka {
20constexpr double kDeltaT = 1e-3;
24constexpr double kLimitEps = 1e-3;
28constexpr double kNormEps = std::numeric_limits<double>::epsilon();
35constexpr double kTolNumberPacketsLost = 0.0;
43constexpr std::array<double, 7> kMaxTorqueRate{
44 {1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps, 1000 - kLimitEps,
45 1000 - kLimitEps, 1000 - kLimitEps}};
49constexpr std::array<double, 7> kMaxJointJerk{
50 {5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps,
51 5000.0 - kLimitEps, 5000.0 - kLimitEps, 5000.0 - kLimitEps}};
55constexpr std::array<double, 7> kMaxJointAcceleration{
56 {10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps,
57 10.0000 - kLimitEps, 10.0000 - kLimitEps, 10.0000 - kLimitEps}};
73constexpr double kMaxTranslationalJerk = 4500.0 - kLimitEps;
77constexpr double kMaxTranslationalAcceleration = 9.0000 - kLimitEps;
81constexpr double kMaxTranslationalVelocity =
86constexpr double kMaxRotationalJerk = 8500.0 - kLimitEps;
90constexpr double kMaxRotationalAcceleration = 17.0000 - kLimitEps;
94constexpr double kMaxRotationalVelocity =
99constexpr double kMaxElbowJerk = 5000 - kLimitEps;
103constexpr double kMaxElbowAcceleration = 10.0000 - kLimitEps;
104
108constexpr double kMaxElbowVelocity =
110
115
130[[deprecated(
131 "Use Robot::getUpperJointVelocityLimits(const std::array<double, 7UL> &joint_positions) "
132 "instead with system images >= 5.9.0.")]] inline std::array<double, 7>
134 const std::array<double, 7>& q) { // NOLINT(readability-identifier-length)
135 return std::array<double, 7>{
136 std::min(2.62, std::max(0.0, -0.30 + std::sqrt(std::max(0.0, 12.0 * (2.75010 - q[0]))))) -
138 std::min(2.62, std::max(0.0, -0.20 + std::sqrt(std::max(0.0, 5.17 * (1.79180 - q[1]))))) -
140 std::min(2.62, std::max(0.0, -0.20 + std::sqrt(std::max(0.0, 7.00 * (2.90650 - q[2]))))) -
142 std::min(2.62, std::max(0.0, -0.30 + std::sqrt(std::max(0.0, 8.00 * (-0.1458 - q[3]))))) -
144 std::min(5.26, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 34.0 * (2.81010 - q[4]))))) -
146 std::min(4.18, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 11.0 * (4.52050 - q[5]))))) -
148 std::min(5.26, std::max(0.0, -0.35 + std::sqrt(std::max(0.0, 34.0 * (3.01960 - q[6]))))) -
150 };
151}
152
167[[deprecated(
168 "Use Robot::getlowerJointVelocityLimits(const std::array<double, 7UL> &joint_positions) "
169 "instead with system images >= 5.9.0.")]] inline std::array<double, 7>
171 const std::array<double, 7>& q) { // NOLINT(readability-identifier-length)
172 return std::array<double, 7>{
173 std::max(-2.62, std::min(0.0, 0.30 - std::sqrt(std::max(0.0, 12.0 * (2.750100 + q[0]))))) +
175 std::max(-2.62, std::min(0.0, 0.20 - std::sqrt(std::max(0.0, 5.17 * (1.791800 + q[1]))))) +
177 std::max(-2.62, std::min(0.0, 0.20 - std::sqrt(std::max(0.0, 7.00 * (2.906500 + q[2]))))) +
179 std::max(-2.62, std::min(0.0, 0.30 - std::sqrt(std::max(0.0, 8.00 * (3.048100 + q[3]))))) +
181 std::max(-5.26, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 34.0 * (2.810100 + q[4]))))) +
183 std::max(-4.18, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 11.0 * (-0.54092 + q[5]))))) +
185 std::max(-5.26, std::min(0.0, 0.35 - std::sqrt(std::max(0.0, 34.0 * (3.019600 + q[6]))))) +
187 };
188}
189
205std::array<double, 7> limitRate(const std::array<double, 7>& max_derivatives,
206 const std::array<double, 7>& commanded_values,
207 const std::array<double, 7>& last_commanded_values);
208
227double limitRate(double upper_limits_velocity,
228 double lower_limits_velocity,
229 double max_acceleration,
230 double max_jerk,
231 double commanded_velocity,
232 double last_commanded_velocity,
233 double last_commanded_acceleration);
234
254double limitRate(double upper_limits_velocity,
255 double lower_limits_velocity,
256 double max_acceleration,
257 double max_jerk,
258 double commanded_position,
259 double last_commanded_position,
260 double last_commanded_velocity,
261 double last_commanded_acceleration);
262
281std::array<double, 7> limitRate(const std::array<double, 7>& upper_limits_velocity,
282 const std::array<double, 7>& lower_limits_velocity,
283 const std::array<double, 7>& max_acceleration,
284 const std::array<double, 7>& max_jerk,
285 const std::array<double, 7>& commanded_velocities,
286 const std::array<double, 7>& last_commanded_velocities,
287 const std::array<double, 7>& last_commanded_accelerations);
288
308std::array<double, 7> limitRate(const std::array<double, 7>& upper_limits_velocity,
309 const std::array<double, 7>& lower_limits_velocity,
310 const std::array<double, 7>& max_acceleration,
311 const std::array<double, 7>& max_jerk,
312 const std::array<double, 7>& commanded_positions,
313 const std::array<double, 7>& last_commanded_positions,
314 const std::array<double, 7>& last_commanded_velocities,
315 const std::array<double, 7>& last_commanded_accelerations);
316
337std::array<double, 6> limitRate(
338 double max_translational_velocity,
339 double max_translational_acceleration,
340 double max_translational_jerk,
341 double max_rotational_velocity,
342 double max_rotational_acceleration,
343 double max_rotational_jerk,
344 const std::array<double, 6>& O_dP_EE_c, // NOLINT(readability-identifier-naming)
345 const std::array<double, 6>& last_O_dP_EE_c, // NOLINT(readability-identifier-naming)
346 const std::array<double, 6>& last_O_ddP_EE_c); // NOLINT(readability-identifier-naming)
347
369std::array<double, 16> limitRate(
370 double max_translational_velocity,
371 double max_translational_acceleration,
372 double max_translational_jerk,
373 double max_rotational_velocity,
374 double max_rotational_acceleration,
375 double max_rotational_jerk,
376 const std::array<double, 16>& O_T_EE_c, // NOLINT(readability-identifier-naming)
377 const std::array<double, 16>& last_O_T_EE_c, // NOLINT(readability-identifier-naming)
378 const std::array<double, 6>& last_O_dP_EE_c, // NOLINT(readability-identifier-naming)
379 const std::array<double, 6>& last_O_ddP_EE_c); // NOLINT(readability-identifier-naming)
380
381} // namespace franka
std::array< double, 7 > computeLowerLimitsJointVelocity(const std::array< double, 7 > &q)
Computes the minimum joint velocity based on joint position.
Definition rate_limiting.h:170
constexpr double kFactorCartesianRotationPoseInterface
Factor for the definition of rotational limits using the Cartesian Pose interface.
Definition rate_limiting.h:39
constexpr double kDeltaT
Sample time constant.
Definition rate_limiting.h:20
constexpr double kMaxRotationalJerk
Maximum rotational jerk.
Definition rate_limiting.h:86
constexpr double kMaxElbowVelocity
Maximum elbow velocity.
Definition rate_limiting.h:108
constexpr double kMaxTranslationalAcceleration
Maximum translational acceleration.
Definition rate_limiting.h:77
constexpr std::array< double, 7 > kJointVelocityLimitsTolerance
Tolerance value for joint velocity limits to deal with numerical errors and data losses.
Definition rate_limiting.h:61
constexpr double kNormEps
Epsilon value for limiting Cartesian accelerations/jerks or not.
Definition rate_limiting.h:28
constexpr double kMaxTranslationalJerk
Maximum translational jerk.
Definition rate_limiting.h:73
constexpr double kMaxRotationalAcceleration
Maximum rotational acceleration.
Definition rate_limiting.h:90
constexpr std::array< double, 7 > kMaxJointJerk
Maximum joint jerk.
Definition rate_limiting.h:49
constexpr double kMinElbowVelocity
Minimum elbow velocity.
Definition rate_limiting.h:114
constexpr double kTolNumberPacketsLost
Number of packets lost considered for the definition of velocity limits.
Definition rate_limiting.h:35
constexpr std::array< double, 7 > kMaxTorqueRate
Maximum torque rate.
Definition rate_limiting.h:43
std::array< double, 7 > limitRate(const std::array< double, 7 > &max_derivatives, const std::array< double, 7 > &commanded_values, const std::array< double, 7 > &last_commanded_values)
Limits the rate of an input vector of per-joint commands considering the maximum allowed time derivat...
constexpr std::array< double, 7 > kMaxJointAcceleration
Maximum joint acceleration.
Definition rate_limiting.h:55
constexpr double kMaxTranslationalVelocity
Maximum translational velocity.
Definition rate_limiting.h:81
constexpr double kLimitEps
Epsilon value for checking limits.
Definition rate_limiting.h:24
constexpr double kMaxRotationalVelocity
Maximum rotational velocity.
Definition rate_limiting.h:94
std::array< double, 7 > computeUpperLimitsJointVelocity(const std::array< double, 7 > &q)
Computes the maximum joint velocity based on joint position.
Definition rate_limiting.h:133
constexpr double kMaxElbowJerk
Maximum elbow jerk.
Definition rate_limiting.h:99
constexpr double kMaxElbowAcceleration
Maximum elbow acceleration.
Definition rate_limiting.h:103