ros2_control - jazzy
Loading...
Searching...
No Matches
rate_limiter.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
15/*
16 * Author: Enrique Fernández
17 */
18
19#ifndef CONTROL_TOOLBOX__RATE_LIMITER_HPP_
20#define CONTROL_TOOLBOX__RATE_LIMITER_HPP_
21
22#include <cmath>
23#include <limits>
24
25#include <algorithm>
26#include <stdexcept>
27
28namespace control_toolbox
29{
30template <typename T>
32{
33public:
59 T min_value = std::numeric_limits<T>::quiet_NaN(),
60 T max_value = std::numeric_limits<T>::quiet_NaN(),
61 T min_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
62 T max_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
63 T min_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
64 T max_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
65 T min_second_derivative = std::numeric_limits<T>::quiet_NaN(),
66 T max_second_derivative = std::numeric_limits<T>::quiet_NaN());
67
76 T limit(T & v, T v0, T v1, T dt);
77
83 T limit_value(T & v);
84
92 T limit_first_derivative(T & v, T v0, T dt);
93
105 T limit_second_derivative(T & v, T v0, T v1, T dt);
106
125 T min_value = std::numeric_limits<T>::quiet_NaN(),
126 T max_value = std::numeric_limits<T>::quiet_NaN(),
127 T min_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
128 T max_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
129 T min_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
130 T max_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
131 T min_second_derivative = std::numeric_limits<T>::quiet_NaN(),
132 T max_second_derivative = std::numeric_limits<T>::quiet_NaN());
133
134private:
135 // Enable/Disable value/first_derivative/second_derivative limits:
136 bool has_value_limits_ = true;
137 bool has_first_derivative_limits_ = true;
138 bool has_second_derivative_limits_ = true;
139
140 // value limits:
141 T min_value_ = std::numeric_limits<T>::quiet_NaN();
142 T max_value_ = std::numeric_limits<T>::quiet_NaN();
143
144 // first_derivative limits:
145 T min_first_derivative_neg_ = std::numeric_limits<T>::quiet_NaN();
146 T max_first_derivative_pos_ = std::numeric_limits<T>::quiet_NaN();
147 T min_first_derivative_pos_ = std::numeric_limits<T>::quiet_NaN();
148 T max_first_derivative_neg_ = std::numeric_limits<T>::quiet_NaN();
149
150 // second_derivative limits:
151 T min_second_derivative_ = std::numeric_limits<T>::quiet_NaN();
152 T max_second_derivative_ = std::numeric_limits<T>::quiet_NaN();
153};
154
155template <typename T>
166
167// Check if limits are valid, max must be specified, min defaults to -max if unspecified
168template <typename T>
173{
174 min_value_ = min_value;
175 max_value_ = max_value;
176 min_first_derivative_neg_ = min_first_derivative_neg;
177 max_first_derivative_pos_ = max_first_derivative_pos;
178 min_first_derivative_pos_ = min_first_derivative_pos;
179 max_first_derivative_neg_ = max_first_derivative_neg;
180 min_second_derivative_ = min_second_derivative;
181 max_second_derivative_ = max_second_derivative;
182
183 if (std::isnan(max_value_))
184 {
185 has_value_limits_ = false;
186 }
187 if (std::isnan(min_value_))
188 {
189 min_value_ = -max_value_;
190 }
191 if (has_value_limits_ && min_value_ > max_value_)
192 {
193 throw std::invalid_argument("Invalid value limits");
194 }
195
196 if (std::isnan(max_first_derivative_pos_))
197 {
198 has_first_derivative_limits_ = false;
199 }
200 if (std::isnan(min_first_derivative_neg_))
201 {
202 min_first_derivative_neg_ = -max_first_derivative_pos_;
203 }
204 if (has_first_derivative_limits_ && min_first_derivative_neg_ > max_first_derivative_pos_)
205 {
206 throw std::invalid_argument("Invalid first derivative limits");
207 }
208 if (has_first_derivative_limits_)
209 {
210 if (std::isnan(max_first_derivative_neg_))
211 {
212 max_first_derivative_neg_ = max_first_derivative_pos_;
213 }
214 if (std::isnan(min_first_derivative_pos_))
215 {
216 min_first_derivative_pos_ = min_first_derivative_neg_;
217 }
218 if (has_first_derivative_limits_ && min_first_derivative_pos_ > max_first_derivative_neg_)
219 {
220 throw std::invalid_argument("Invalid first derivative limits");
221 }
222 }
223
224 if (std::isnan(max_second_derivative_))
225 {
226 has_second_derivative_limits_ = false;
227 }
228 if (std::isnan(min_second_derivative_))
229 {
230 min_second_derivative_ = -max_second_derivative_;
231 }
232 if (has_second_derivative_limits_ && min_second_derivative_ > max_second_derivative_)
233 {
234 throw std::invalid_argument("Invalid second derivative limits");
235 }
236}
237
238template <typename T>
239T RateLimiter<T>::limit(T & v, T v0, T v1, T dt)
240{
241 const T tmp = v;
242
243 limit_second_derivative(v, v0, v1, dt);
244 limit_first_derivative(v, v0, dt);
245 limit_value(v);
246
247 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
248}
249
250template <typename T>
252{
253 const T tmp = v;
254
255 if (has_value_limits_)
256 {
257 v = std::clamp(v, min_value_, max_value_);
258 }
259
260 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
261}
262
263template <typename T>
265{
266 const T tmp = v;
267
268 if (has_first_derivative_limits_)
269 {
270 T dv_max, dv_min = 0;
271 if (v0 > static_cast<T>(0.0))
272 {
273 dv_max = max_first_derivative_pos_ * dt;
274 dv_min = min_first_derivative_pos_ * dt;
275 }
276 else if (v0 < static_cast<T>(0.0))
277 {
278 dv_min = min_first_derivative_neg_ * dt;
279 dv_max = max_first_derivative_neg_ * dt;
280 }
281 else
282 {
283 dv_min = min_first_derivative_neg_ * dt;
284 dv_max = max_first_derivative_pos_ * dt;
285 }
286 const T dv = std::clamp(v - v0, dv_min, dv_max);
287
288 v = v0 + dv;
289 }
290
291 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
292}
293
294template <typename T>
296{
297 const T tmp = v;
298
299 if (has_second_derivative_limits_)
300 {
301 const T dv = v - v0;
302 const T dv0 = v0 - v1;
303
304 // Only limit jerk when accelerating or reverse_accelerating
305 // Note: this prevents oscillating closed-loop behavior, see discussion
306 // details in https://github.com/ros-controls/control_toolbox/issues/240.
307 if ((dv - dv0) * (v - v0) > 0)
308 {
309 const T dt2 = dt * dt;
310
311 const T da_min = min_second_derivative_ * dt2;
312 const T da_max = max_second_derivative_ * dt2;
313
314 const T da = std::clamp(dv - dv0, da_min, da_max);
315
316 v = v0 + dv0 + da;
317 }
318 }
319
320 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
321}
322
323} // namespace control_toolbox
324
325#endif // CONTROL_TOOLBOX__RATE_LIMITER_HPP_
A Low-pass filter class.
Definition low_pass_filter.hpp:78
void set_params(double sampling_frequency, double damping_frequency, double damping_intensity)
Internal computation of the feedforward and feedbackward coefficients according to the LowPassFilter ...
Definition low_pass_filter.hpp:114
Definition rate_limiter.hpp:32
T limit_value(T &v)
Limit the value.
Definition rate_limiter.hpp:251
T limit_second_derivative(T &v, T v0, T v1, T dt)
Limit the second_derivative.
Definition rate_limiter.hpp:295
T limit(T &v, T v0, T v1, T dt)
Limit the value, first_derivative, and second_derivative.
Definition rate_limiter.hpp:239
void set_params(T min_value=std::numeric_limits< T >::quiet_NaN(), T max_value=std::numeric_limits< T >::quiet_NaN(), T min_first_derivative_neg=std::numeric_limits< T >::quiet_NaN(), T max_first_derivative_pos=std::numeric_limits< T >::quiet_NaN(), T min_first_derivative_pos=std::numeric_limits< T >::quiet_NaN(), T max_first_derivative_neg=std::numeric_limits< T >::quiet_NaN(), T min_second_derivative=std::numeric_limits< T >::quiet_NaN(), T max_second_derivative=std::numeric_limits< T >::quiet_NaN())
Set the parameters.
Definition rate_limiter.hpp:169
RateLimiter(T min_value=std::numeric_limits< T >::quiet_NaN(), T max_value=std::numeric_limits< T >::quiet_NaN(), T min_first_derivative_neg=std::numeric_limits< T >::quiet_NaN(), T max_first_derivative_pos=std::numeric_limits< T >::quiet_NaN(), T min_first_derivative_pos=std::numeric_limits< T >::quiet_NaN(), T max_first_derivative_neg=std::numeric_limits< T >::quiet_NaN(), T min_second_derivative=std::numeric_limits< T >::quiet_NaN(), T max_second_derivative=std::numeric_limits< T >::quiet_NaN())
Constructor.
Definition rate_limiter.hpp:156
T limit_first_derivative(T &v, T v0, T dt)
Limit the first_derivative.
Definition rate_limiter.hpp:264
Definition dither.hpp:46