ros2_control - humble
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
107
125 void set_params(
126 T min_value = std::numeric_limits<T>::quiet_NaN(),
127 T max_value = std::numeric_limits<T>::quiet_NaN(),
128 T min_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
129 T max_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
130 T min_first_derivative_pos = std::numeric_limits<T>::quiet_NaN(),
131 T max_first_derivative_neg = std::numeric_limits<T>::quiet_NaN(),
132 T min_second_derivative = std::numeric_limits<T>::quiet_NaN(),
133 T max_second_derivative = std::numeric_limits<T>::quiet_NaN());
134
135private:
136 // Enable/Disable value/first_derivative/second_derivative limits:
137 bool has_value_limits_ = true;
138 bool has_first_derivative_limits_ = true;
139 bool has_second_derivative_limits_ = true;
140
141 // value limits:
142 T min_value_ = std::numeric_limits<T>::quiet_NaN();
143 T max_value_ = std::numeric_limits<T>::quiet_NaN();
144
145 // first_derivative limits:
146 T min_first_derivative_neg_ = std::numeric_limits<T>::quiet_NaN();
147 T max_first_derivative_pos_ = std::numeric_limits<T>::quiet_NaN();
148 T min_first_derivative_pos_ = std::numeric_limits<T>::quiet_NaN();
149 T max_first_derivative_neg_ = std::numeric_limits<T>::quiet_NaN();
150
151 // second_derivative limits:
152 T min_second_derivative_ = std::numeric_limits<T>::quiet_NaN();
153 T max_second_derivative_ = std::numeric_limits<T>::quiet_NaN();
154};
155
156template <typename T>
158 T min_value, T max_value,
159 T min_first_derivative_neg, T max_first_derivative_pos,
160 T min_first_derivative_pos, T max_first_derivative_neg,
161 T min_second_derivative, T max_second_derivative)
162{
163 set_params(
164 min_value, max_value,
165 min_first_derivative_neg, max_first_derivative_pos,
166 min_first_derivative_pos, max_first_derivative_neg,
167 min_second_derivative, max_second_derivative
168 );
169};
170
171// Check if limits are valid, max must be specified, min defaults to -max if unspecified
172template <typename T>
174 T min_value, T max_value,
175 T min_first_derivative_neg, T max_first_derivative_pos,
176 T min_first_derivative_pos, T max_first_derivative_neg,
177 T min_second_derivative, T max_second_derivative)
178 {
179 min_value_ = min_value;
180 max_value_ = max_value;
181 min_first_derivative_neg_ = min_first_derivative_neg;
182 max_first_derivative_pos_ = max_first_derivative_pos;
183 min_first_derivative_pos_ = min_first_derivative_pos;
184 max_first_derivative_neg_ = max_first_derivative_neg;
185 min_second_derivative_ = min_second_derivative;
186 max_second_derivative_ = max_second_derivative;
187
188 if (std::isnan(max_value_))
189 {
190 has_value_limits_ = false;
191 }
192 if (std::isnan(min_value_))
193 {
194 min_value_ = -max_value_;
195 }
196 if (has_value_limits_ && min_value_ > max_value_)
197 {
198 throw std::invalid_argument("Invalid value limits");
199 }
200
201 if (std::isnan(max_first_derivative_pos_))
202 {
203 has_first_derivative_limits_ = false;
204 }
205 if (std::isnan(min_first_derivative_neg_))
206 {
207 min_first_derivative_neg_ = -max_first_derivative_pos_;
208 }
209 if (has_first_derivative_limits_ && min_first_derivative_neg_ > max_first_derivative_pos_)
210 {
211 throw std::invalid_argument("Invalid first derivative limits");
212 }
213 if (has_first_derivative_limits_)
214 {
215 if (std::isnan(max_first_derivative_neg_))
216 {
217 max_first_derivative_neg_ = max_first_derivative_pos_;
218 }
219 if (std::isnan(min_first_derivative_pos_))
220 {
221 min_first_derivative_pos_ = min_first_derivative_neg_;
222 }
223 if (has_first_derivative_limits_ && min_first_derivative_pos_ > max_first_derivative_neg_)
224 {
225 throw std::invalid_argument("Invalid first derivative limits");
226 }
227 }
228
229 if (std::isnan(max_second_derivative_))
230 {
231 has_second_derivative_limits_ = false;
232 }
233 if (std::isnan(min_second_derivative_))
234 {
235 min_second_derivative_ = -max_second_derivative_;
236 }
237 if (has_second_derivative_limits_ && min_second_derivative_ > max_second_derivative_)
238 {
239 throw std::invalid_argument("Invalid second derivative limits");
240 }
241}
242
243template <typename T>
244T RateLimiter<T>::limit(T & v, T v0, T v1, T dt)
245{
246 const T tmp = v;
247
248 limit_second_derivative(v, v0, v1, dt);
249 limit_first_derivative(v, v0, dt);
250 limit_value(v);
251
252 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
253}
254
255template <typename T>
257{
258 const T tmp = v;
259
260 if (has_value_limits_)
261 {
262 v = std::clamp(v, min_value_, max_value_);
263 }
264
265 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
266}
267
268template <typename T>
270{
271 const T tmp = v;
272
273 if (has_first_derivative_limits_)
274 {
275 T dv_max, dv_min = 0;
276 if (v0 > static_cast<T>(0.0))
277 {
278 dv_max = max_first_derivative_pos_ * dt;
279 dv_min = min_first_derivative_pos_ * dt;
280 }
281 else if (v0 < static_cast<T>(0.0))
282 {
283 dv_min = min_first_derivative_neg_ * dt;
284 dv_max = max_first_derivative_neg_ * dt;
285 }
286 else
287 {
288 dv_min = min_first_derivative_neg_ * dt;
289 dv_max = max_first_derivative_pos_ * dt;
290 }
291 const T dv = std::clamp(v - v0, dv_min, dv_max);
292
293 v = v0 + dv;
294 }
295
296 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
297}
298
299template <typename T>
301{
302 const T tmp = v;
303
304 if (has_second_derivative_limits_)
305 {
306 const T dv = v - v0;
307 const T dv0 = v0 - v1;
308
309 // Only limit jerk when accelerating or reverse_accelerating
310 // Note: this prevents oscillating closed-loop behavior, see discussion
311 // details in https://github.com/ros-controls/control_toolbox/issues/240.
312 if ((dv - dv0) * (v - v0) > 0)
313 {
314 const T dt2 = dt * dt;
315
316 const T da_min = min_second_derivative_ * dt2;
317 const T da_max = max_second_derivative_ * dt2;
318
319 const T da = std::clamp(dv - dv0, da_min, da_max);
320
321 v = v0 + dv0 + da;
322 }
323 }
324
325 return tmp != static_cast<T>(0.0) ? v / tmp : static_cast<T>(1.0);
326}
327
328} // namespace control_toolbox
329
330#endif // CONTROL_TOOLBOX__RATE_LIMITER_HPP_
Definition rate_limiter.hpp:32
T limit_value(T &v)
Limit the value.
Definition rate_limiter.hpp:256
T limit_second_derivative(T &v, T v0, T v1, T dt)
Limit the second_derivative.
Definition rate_limiter.hpp:300
T limit(T &v, T v0, T v1, T dt)
Limit the value and first_derivative.
Definition rate_limiter.hpp:244
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:173
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:157
T limit_first_derivative(T &v, T v0, T dt)
Limit the first_derivative.
Definition rate_limiter.hpp:269
Definition dither.hpp:46