CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/APM_Control/AR_AttitudeControl.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include <AP_AHRS/AP_AHRS.h>
17
#include <AP_Math/AP_Math.h>
18
#include <AP_HAL/AP_HAL.h>
19
#include "AR_AttitudeControl.h"
20
#include <AP_GPS/AP_GPS.h>
21
22
// attitude control default definition
23
#define AR_ATTCONTROL_STEER_ANG_P 2.00f
24
#define AR_ATTCONTROL_STEER_RATE_FF 0.20f
25
#define AR_ATTCONTROL_STEER_RATE_P 0.20f
26
#define AR_ATTCONTROL_STEER_RATE_I 0.20f
27
#define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
28
#define AR_ATTCONTROL_STEER_RATE_D 0.00f
29
#define AR_ATTCONTROL_STEER_RATE_FILT 10.00f
30
#define AR_ATTCONTROL_STEER_RATE_MAX 120.0f
31
#define AR_ATTCONTROL_STEER_ACCEL_MAX 120.0f
32
#define AR_ATTCONTROL_THR_SPEED_P 0.20f
33
#define AR_ATTCONTROL_THR_SPEED_I 0.20f
34
#define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
35
#define AR_ATTCONTROL_THR_SPEED_D 0.00f
36
#define AR_ATTCONTROL_THR_SPEED_FILT 10.00f
37
#define AR_ATTCONTROL_PITCH_THR_P 1.80f
38
#define AR_ATTCONTROL_PITCH_THR_I 1.50f
39
#define AR_ATTCONTROL_PITCH_THR_D 0.03f
40
#define AR_ATTCONTROL_PITCH_THR_IMAX 1.0f
41
#define AR_ATTCONTROL_PITCH_THR_FILT 10.0f
42
#define AR_ATTCONTROL_BAL_PITCH_FF 0.4f
43
#define AR_ATTCONTROL_PITCH_LIM_TC 0.5f // pitch limit default time constant
44
#define AR_ATTCONTROL_PITCH_RELAX_RATIO 0.5f // pitch limit relaxed 2x slower than it is limited
45
#define AR_ATTCONTROL_PITCH_LIM_THR_THRESH 0.60 // pitch limiting starts if throttle exceeds 60%
46
#define AR_ATTCONTROL_DT 0.02f
47
#define AR_ATTCONTROL_TIMEOUT_MS 200
48
#define AR_ATTCONTROL_HEEL_SAIL_P 1.0f
49
#define AR_ATTCONTROL_HEEL_SAIL_I 0.1f
50
#define AR_ATTCONTROL_HEEL_SAIL_D 0.0f
51
#define AR_ATTCONTROL_HEEL_SAIL_IMAX 1.0f
52
#define AR_ATTCONTROL_HEEL_SAIL_FILT 10.0f
53
#define AR_ATTCONTROL_DT 0.02f
54
55
// throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
56
#define AR_ATTCONTROL_THR_ACCEL_MAX 1.00f
57
58
// minimum speed in m/s
59
#define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
60
61
// speed (in m/s) at or below which vehicle is considered stopped (_STOP_SPEED parameter default)
62
#define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
63
64
extern const AP_HAL::HAL& hal;
65
66
AR_AttitudeControl *AR_AttitudeControl::_singleton;
67
68
const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
69
70
// @Param: _STR_RAT_P
71
// @DisplayName: Steering control rate P gain
72
// @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
73
// @Range: 0.000 2.000
74
// @Increment: 0.001
75
// @User: Standard
76
77
// @Param: _STR_RAT_I
78
// @DisplayName: Steering control I gain
79
// @Description: Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
80
// @Range: 0.000 2.000
81
// @Increment: 0.001
82
// @User: Standard
83
84
// @Param: _STR_RAT_IMAX
85
// @DisplayName: Steering control I gain maximum
86
// @Description: Steering control I gain maximum. Constrains the steering output (range -1 to +1) that the I term will generate
87
// @Range: 0.000 1.000
88
// @Increment: 0.01
89
// @User: Standard
90
91
// @Param: _STR_RAT_D
92
// @DisplayName: Steering control D gain
93
// @Description: Steering control D gain. Compensates for short-term change in desired turn rate vs actual
94
// @Range: 0.000 0.400
95
// @Increment: 0.001
96
// @User: Standard
97
98
// @Param: _STR_RAT_FF
99
// @DisplayName: Steering control feed forward
100
// @Description: Steering control feed forward
101
// @Range: 0.000 3.000
102
// @Increment: 0.001
103
// @User: Standard
104
105
// @Param: _STR_RAT_FILT
106
// @DisplayName: Steering control filter frequency
107
// @Description: Steering control input filter. Lower values reduce noise but add delay.
108
// @Range: 0.000 100.000
109
// @Increment: 0.1
110
// @Units: Hz
111
// @User: Standard
112
113
// @Param: _STR_RAT_FLTT
114
// @DisplayName: Steering control Target filter frequency in Hz
115
// @Description: Target filter frequency in Hz
116
// @Range: 0.000 100.000
117
// @Increment: 0.1
118
// @Units: Hz
119
// @User: Standard
120
121
// @Param: _STR_RAT_FLTE
122
// @DisplayName: Steering control Error filter frequency in Hz
123
// @Description: Error filter frequency in Hz
124
// @Range: 0.000 100.000
125
// @Increment: 0.1
126
// @Units: Hz
127
// @User: Standard
128
129
// @Param: _STR_RAT_FLTD
130
// @DisplayName: Steering control Derivative term filter frequency in Hz
131
// @Description: Derivative filter frequency in Hz
132
// @Range: 0.000 100.000
133
// @Increment: 0.1
134
// @Units: Hz
135
// @User: Standard
136
137
// @Param: _STR_RAT_SMAX
138
// @DisplayName: Steering slew rate limit
139
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
140
// @Range: 0 200
141
// @Increment: 0.5
142
// @User: Advanced
143
144
// @Param: _STR_RAT_PDMX
145
// @DisplayName: Steering control PD sum maximum
146
// @Description: Steering control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
147
// @Range: 0.000 1.000
148
// @Increment: 0.01
149
150
// @Param: _STR_RAT_D_FF
151
// @DisplayName: Steering control Derivative FeedForward Gain
152
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
153
// @Range: 0 0.03
154
// @Increment: 0.001
155
// @User: Advanced
156
157
// @Param: _STR_RAT_NTF
158
// @DisplayName: Steering control Target notch filter index
159
// @Description: Steering control Target notch filter index
160
// @Range: 1 8
161
// @User: Advanced
162
163
// @Param: _STR_RAT_NEF
164
// @DisplayName: Steering control Error notch filter index
165
// @Description: Steering control Error notch filter index
166
// @Range: 1 8
167
// @User: Advanced
168
169
AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
170
171
// @Param: _SPEED_P
172
// @DisplayName: Speed control P gain
173
// @Description: Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
174
// @Range: 0.010 2.000
175
// @Increment: 0.01
176
// @User: Standard
177
178
// @Param: _SPEED_I
179
// @DisplayName: Speed control I gain
180
// @Description: Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
181
// @Range: 0.000 2.000
182
// @Increment: 0.01
183
// @User: Standard
184
185
// @Param: _SPEED_IMAX
186
// @DisplayName: Speed control I gain maximum
187
// @Description: Speed control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
188
// @Range: 0.000 1.000
189
// @Increment: 0.01
190
// @User: Standard
191
192
// @Param: _SPEED_D
193
// @DisplayName: Speed control D gain
194
// @Description: Speed control D gain. Compensates for short-term change in desired speed vs actual
195
// @Range: 0.000 0.400
196
// @Increment: 0.001
197
// @User: Standard
198
199
// @Param: _SPEED_FF
200
// @DisplayName: Speed control feed forward
201
// @Description: Speed control feed forward
202
// @Range: 0.000 0.500
203
// @Increment: 0.001
204
// @User: Standard
205
206
// @Param: _SPEED_FILT
207
// @DisplayName: Speed control filter frequency
208
// @Description: Speed control input filter. Lower values reduce noise but add delay.
209
// @Range: 0.000 100.000
210
// @Increment: 0.1
211
// @Units: Hz
212
// @User: Standard
213
214
// @Param: _SPEED_FLTT
215
// @DisplayName: Speed control Target filter frequency in Hz
216
// @Description: Target filter frequency in Hz
217
// @Range: 0.000 100.000
218
// @Increment: 0.1
219
// @Units: Hz
220
// @User: Standard
221
222
// @Param: _SPEED_FLTE
223
// @DisplayName: Speed control Error filter frequency in Hz
224
// @Description: Error filter frequency in Hz
225
// @Range: 0.000 100.000
226
// @Increment: 0.1
227
// @Units: Hz
228
// @User: Standard
229
230
// @Param: _SPEED_FLTD
231
// @DisplayName: Speed control Derivative term filter frequency in Hz
232
// @Description: Derivative filter frequency in Hz
233
// @Range: 0.000 100.000
234
// @Increment: 0.1
235
// @Units: Hz
236
// @User: Standard
237
238
// @Param: _SPEED_SMAX
239
// @DisplayName: Speed control slew rate limit
240
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
241
// @Range: 0 200
242
// @Increment: 0.5
243
// @User: Advanced
244
245
// @Param: _SPEED_PDMX
246
// @DisplayName: Speed control PD sum maximum
247
// @Description: Speed control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
248
// @Range: 0.000 1.000
249
// @Increment: 0.01
250
251
// @Param: _SPEED_D_FF
252
// @DisplayName: Speed control Derivative FeedForward Gain
253
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
254
// @Range: 0 0.03
255
// @Increment: 0.001
256
// @User: Advanced
257
258
// @Param: _SPEED_NTF
259
// @DisplayName: Speed control Target notch filter index
260
// @Description: Speed control Target notch filter index
261
// @Range: 1 8
262
// @User: Advanced
263
264
// @Param: _SPEED_NEF
265
// @DisplayName: Speed control Error notch filter index
266
// @Description: Speed control Error notch filter index
267
// @Range: 1 8
268
// @User: Advanced
269
270
AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
271
272
// @Param: _ACCEL_MAX
273
// @DisplayName: Speed control acceleration (and deceleration) maximum in m/s/s
274
// @Description: Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
275
// @Range: 0.0 10.0
276
// @Increment: 0.1
277
// @Units: m/s/s
278
// @User: Standard
279
AP_GROUPINFO("_ACCEL_MAX", 3, AR_AttitudeControl, _throttle_accel_max, AR_ATTCONTROL_THR_ACCEL_MAX),
280
281
// @Param: _BRAKE
282
// @DisplayName: Speed control brake enable/disable
283
// @Description: Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
284
// @Values: 0:Disable,1:Enable
285
// @User: Standard
286
AP_GROUPINFO("_BRAKE", 4, AR_AttitudeControl, _brake_enable, 1),
287
288
// @Param: _STOP_SPEED
289
// @DisplayName: Speed control stop speed
290
// @Description: Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
291
// @Range: 0.00 0.50
292
// @Increment: 0.01
293
// @Units: m/s
294
// @User: Standard
295
AP_GROUPINFO("_STOP_SPEED", 5, AR_AttitudeControl, _stop_speed, AR_ATTCONTROL_STOP_SPEED_DEFAULT),
296
297
// @Param: _STR_ANG_P
298
// @DisplayName: Steering control angle P gain
299
// @Description: Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
300
// @Range: 1.000 10.000
301
// @Increment: 0.1
302
// @User: Standard
303
AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 6, AR_AttitudeControl, AC_P),
304
305
// @Param: _STR_ACC_MAX
306
// @DisplayName: Steering control angular acceleration maximum
307
// @Description: Steering control angular acceleration maximum (in deg/s/s). 0 to disable acceleration limiting
308
// @Range: 0 1000
309
// @Increment: 0.1
310
// @Units: deg/s/s
311
// @User: Standard
312
AP_GROUPINFO("_STR_ACC_MAX", 7, AR_AttitudeControl, _steer_accel_max, AR_ATTCONTROL_STEER_ACCEL_MAX),
313
314
// @Param: _STR_RAT_MAX
315
// @DisplayName: Steering control rotation rate maximum
316
// @Description: Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
317
// @Range: 0 1000
318
// @Increment: 0.1
319
// @Units: deg/s
320
// @User: Standard
321
AP_GROUPINFO("_STR_RAT_MAX", 8, AR_AttitudeControl, _steer_rate_max, AR_ATTCONTROL_STEER_RATE_MAX),
322
323
// @Param: _DECEL_MAX
324
// @DisplayName: Speed control deceleration maximum in m/s/s
325
// @Description: Speed control and deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
326
// @Range: 0.0 10.0
327
// @Increment: 0.1
328
// @Units: m/s/s
329
// @User: Standard
330
AP_GROUPINFO("_DECEL_MAX", 9, AR_AttitudeControl, _throttle_decel_max, 0.00f),
331
332
// @Param: _BAL_P
333
// @DisplayName: Pitch control P gain
334
// @Description: Pitch control P gain for BalanceBots. Converts the error between the desired pitch (in radians) and actual pitch to a motor output (in the range -1 to +1)
335
// @Range: 0.000 2.000
336
// @Increment: 0.01
337
// @User: Standard
338
339
// @Param: _BAL_I
340
// @DisplayName: Pitch control I gain
341
// @Description: Pitch control I gain for BalanceBots. Corrects long term error between the desired pitch (in radians) and actual pitch
342
// @Range: 0.000 2.000
343
// @Increment: 0.01
344
// @User: Standard
345
346
// @Param: _BAL_IMAX
347
// @DisplayName: Pitch control I gain maximum
348
// @Description: Pitch control I gain maximum. Constrains the maximum motor output (range -1 to +1) that the I term will generate
349
// @Range: 0.000 1.000
350
// @Increment: 0.01
351
// @User: Standard
352
353
// @Param: _BAL_D
354
// @DisplayName: Pitch control D gain
355
// @Description: Pitch control D gain. Compensates for short-term change in desired pitch vs actual
356
// @Range: 0.000 0.100
357
// @Increment: 0.001
358
// @User: Standard
359
360
// @Param: _BAL_FF
361
// @DisplayName: Pitch control feed forward
362
// @Description: Pitch control feed forward
363
// @Range: 0.000 0.500
364
// @Increment: 0.001
365
// @User: Standard
366
367
// @Param: _BAL_FILT
368
// @DisplayName: Pitch control filter frequency
369
// @Description: Pitch control input filter. Lower values reduce noise but add delay.
370
// @Range: 0.000 100.000
371
// @Increment: 0.1
372
// @Units: Hz
373
// @User: Standard
374
375
// @Param: _BAL_FLTT
376
// @DisplayName: Pitch control Target filter frequency in Hz
377
// @Description: Pitch control Target filter frequency in Hz
378
// @Range: 0.000 100.000
379
// @Increment: 0.1
380
// @Units: Hz
381
// @User: Standard
382
383
// @Param: _BAL_FLTE
384
// @DisplayName: Pitch control Error filter frequency in Hz
385
// @Description: Pitch control Error filter frequency in Hz
386
// @Range: 0.000 100.000
387
// @Increment: 0.1
388
// @Units: Hz
389
// @User: Standard
390
391
// @Param: _BAL_FLTD
392
// @DisplayName: Pitch control Derivative term filter frequency in Hz
393
// @Description: Pitch control Derivative filter frequency in Hz
394
// @Range: 0.000 100.000
395
// @Increment: 0.1
396
// @Units: Hz
397
// @User: Standard
398
399
// @Param: _BAL_SMAX
400
// @DisplayName: Pitch control slew rate limit
401
// @Description: Pitch control upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
402
// @Range: 0 200
403
// @Increment: 0.5
404
// @User: Advanced
405
406
// @Param: _BAL_PDMX
407
// @DisplayName: Pitch control PD sum maximum
408
// @Description: Pitch control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
409
// @Range: 0.000 1.000
410
// @Increment: 0.01
411
412
// @Param: _BAL_D_FF
413
// @DisplayName: Pitch control Derivative FeedForward Gain
414
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
415
// @Range: 0 0.03
416
// @Increment: 0.001
417
// @User: Advanced
418
419
// @Param: _BAL_NTF
420
// @DisplayName: Pitch control Target notch filter index
421
// @Description: Pitch control Target notch filter index
422
// @Range: 1 8
423
// @User: Advanced
424
425
// @Param: _BAL_NEF
426
// @DisplayName: Pitch control Error notch filter index
427
// @Description: Pitch control Error notch filter index
428
// @Range: 1 8
429
// @User: Advanced
430
431
AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID),
432
433
// @Param: _BAL_PIT_FF
434
// @DisplayName: Pitch control feed forward from current pitch angle
435
// @Description: Pitch control feed forward from current pitch angle
436
// @Range: 0.0 1.0
437
// @Increment: 0.01
438
// @User: Standard
439
AP_GROUPINFO("_BAL_PIT_FF", 11, AR_AttitudeControl, _pitch_to_throttle_ff, AR_ATTCONTROL_BAL_PITCH_FF),
440
441
// @Param: _SAIL_P
442
// @DisplayName: Sail Heel control P gain
443
// @Description: Sail Heel control P gain for sailboats. Converts the error between the desired heel angle (in radians) and actual heel to a main sail output (in the range -1 to +1)
444
// @Range: 0.000 2.000
445
// @Increment: 0.01
446
// @User: Standard
447
448
// @Param: _SAIL_I
449
// @DisplayName: Sail Heel control I gain
450
// @Description: Sail Heel control I gain for sailboats. Corrects long term error between the desired heel angle (in radians) and actual
451
// @Range: 0.000 2.000
452
// @Increment: 0.01
453
// @User: Standard
454
455
// @Param: _SAIL_IMAX
456
// @DisplayName: Sail Heel control I gain maximum
457
// @Description: Sail Heel control I gain maximum. Constrains the maximum I term contribution to the main sail output (range -1 to +1)
458
// @Range: 0.000 1.000
459
// @Increment: 0.01
460
// @User: Standard
461
462
// @Param: _SAIL_D
463
// @DisplayName: Sail Heel control D gain
464
// @Description: Sail Heel control D gain. Compensates for short-term change in desired heel angle vs actual
465
// @Range: 0.000 0.100
466
// @Increment: 0.001
467
// @User: Standard
468
469
// @Param: _SAIL_FF
470
// @DisplayName: Sail Heel control feed forward
471
// @Description: Sail Heel control feed forward
472
// @Range: 0.000 0.500
473
// @Increment: 0.001
474
// @User: Standard
475
476
// @Param: _SAIL_FILT
477
// @DisplayName: Sail Heel control filter frequency
478
// @Description: Sail Heel control input filter. Lower values reduce noise but add delay.
479
// @Range: 0.000 100.000
480
// @Increment: 0.1
481
// @Units: Hz
482
// @User: Standard
483
484
// @Param: _SAIL_FLTT
485
// @DisplayName: Sail Heel Target filter frequency in Hz
486
// @Description: Target filter frequency in Hz
487
// @Range: 0.000 100.000
488
// @Increment: 0.1
489
// @Units: Hz
490
// @User: Standard
491
492
// @Param: _SAIL_FLTE
493
// @DisplayName: Sail Heel Error filter frequency in Hz
494
// @Description: Error filter frequency in Hz
495
// @Range: 0.000 100.000
496
// @Increment: 0.1
497
// @Units: Hz
498
// @User: Standard
499
500
// @Param: _SAIL_FLTD
501
// @DisplayName: Sail Heel Derivative term filter frequency in Hz
502
// @Description: Derivative filter frequency in Hz
503
// @Range: 0.000 100.000
504
// @Increment: 0.1
505
// @Units: Hz
506
// @User: Standard
507
508
// @Param: _SAIL_SMAX
509
// @DisplayName: Sail heel slew rate limit
510
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
511
// @Range: 0 200
512
// @Increment: 0.5
513
// @User: Advanced
514
515
// @Param: _SAIL_PDMX
516
// @DisplayName: Sail Heel control PD sum maximum
517
// @Description: Sail Heel control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
518
// @Range: 0.000 1.000
519
// @Increment: 0.01
520
521
// @Param: _SAIL_D_FF
522
// @DisplayName: Sail Heel Derivative FeedForward Gain
523
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
524
// @Range: 0 0.03
525
// @Increment: 0.001
526
// @User: Advanced
527
528
// @Param: _SAIL_NTF
529
// @DisplayName: Sail Heel Target notch filter index
530
// @Description: Sail Heel Target notch filter index
531
// @Range: 1 8
532
// @User: Advanced
533
534
// @Param: _SAIL_NEF
535
// @DisplayName: Sail Heel Error notch filter index
536
// @Description: Sail Heel Error notch filter index
537
// @Range: 1 8
538
// @User: Advanced
539
540
AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID),
541
542
// @Param: _TURN_MAX_G
543
// @DisplayName: Turning maximum G force
544
// @Description: The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
545
// @Units: gravities
546
// @Range: 0.1 10
547
// @Increment: 0.01
548
// @User: Standard
549
AP_GROUPINFO("_TURN_MAX_G", 13, AR_AttitudeControl, _turn_lateral_G_max, 0.6f),
550
551
// @Param: _BAL_LIM_TC
552
// @DisplayName: Pitch control limit time constant
553
// @Description: Pitch control limit time constant to protect against falling. Lower values limit pitch more quickly, higher values limit more slowly. Set to 0 to disable
554
// @Range: 0.0 5.0
555
// @Increment: 0.01
556
// @User: Standard
557
AP_GROUPINFO("_BAL_LIM_TC", 14, AR_AttitudeControl, _pitch_limit_tc, AR_ATTCONTROL_PITCH_LIM_TC),
558
559
// @Param: _BAL_LIM_THR
560
// @DisplayName: Pitch control limit throttle threshold
561
// @Description: Pitch control limit throttle threshold. Pitch angle will be limited if throttle crosses this threshold (from 0 to 1)
562
// @Range: 0.0 1.0
563
// @Increment: 0.01
564
// @User: Standard
565
AP_GROUPINFO("_BAL_LIM_THR", 15, AR_AttitudeControl, _pitch_limit_throttle_thresh, AR_ATTCONTROL_PITCH_LIM_THR_THRESH),
566
567
AP_GROUPEND
568
};
569
570
AR_AttitudeControl::AR_AttitudeControl() :
571
_steer_angle_p(AR_ATTCONTROL_STEER_ANG_P),
572
_steer_rate_pid(AR_ATTCONTROL_STEER_RATE_P, AR_ATTCONTROL_STEER_RATE_I, AR_ATTCONTROL_STEER_RATE_D, AR_ATTCONTROL_STEER_RATE_FF, AR_ATTCONTROL_STEER_RATE_IMAX, 0.0f, AR_ATTCONTROL_STEER_RATE_FILT, 0.0f),
573
_throttle_speed_pid(AR_ATTCONTROL_THR_SPEED_P, AR_ATTCONTROL_THR_SPEED_I, AR_ATTCONTROL_THR_SPEED_D, 0.0f, AR_ATTCONTROL_THR_SPEED_IMAX, 0.0f, AR_ATTCONTROL_THR_SPEED_FILT, 0.0f),
574
_pitch_to_throttle_pid(AR_ATTCONTROL_PITCH_THR_P, AR_ATTCONTROL_PITCH_THR_I, AR_ATTCONTROL_PITCH_THR_D, 0.0f, AR_ATTCONTROL_PITCH_THR_IMAX, 0.0f, AR_ATTCONTROL_PITCH_THR_FILT, 0.0f),
575
_sailboat_heel_pid(AR_ATTCONTROL_HEEL_SAIL_P, AR_ATTCONTROL_HEEL_SAIL_I, AR_ATTCONTROL_HEEL_SAIL_D, 0.0f, AR_ATTCONTROL_HEEL_SAIL_IMAX, 0.0f, AR_ATTCONTROL_HEEL_SAIL_FILT, 0.0f)
576
{
577
_singleton = this;
578
AP_Param::setup_object_defaults(this, var_info);
579
}
580
581
// return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
582
// positive lateral acceleration is to the right.
583
float AR_AttitudeControl::get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
584
{
585
// record desired accel for reporting purposes
586
_steer_lat_accel_last_ms = AP_HAL::millis();
587
_desired_lat_accel = desired_accel;
588
589
// get speed forward
590
float speed;
591
if (!get_forward_speed(speed)) {
592
// we expect caller will not try to control heading using rate control without a valid speed estimate
593
// on failure to get speed we do not attempt to steer
594
return 0.0f;
595
}
596
597
const float desired_rate = get_turn_rate_from_lat_accel(desired_accel, speed);
598
599
return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
600
}
601
602
// return a steering servo output from -1 to +1 given a heading in radians
603
// set rate_max_rads to a non-zero number to apply a limit on the desired turn rate
604
// return value is normally in range -1.0 to +1.0 but can be higher or lower
605
float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate_max_rads, bool motor_limit_left, bool motor_limit_right, float dt)
606
{
607
// calculate the desired turn rate (in radians) from the angle error (also in radians)
608
float desired_rate = get_turn_rate_from_heading(heading_rad, rate_max_rads);
609
610
return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
611
}
612
613
// return a desired turn-rate given a desired heading in radians
614
float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const
615
{
616
const float yaw_error = wrap_PI(heading_rad - AP::ahrs().get_yaw());
617
618
// Calculate the desired turn rate (in radians) from the angle error (also in radians)
619
float desired_rate = _steer_angle_p.get_p(yaw_error);
620
621
// limit desired_rate if a custom pivot turn rate is selected, otherwise use ATC_STR_RAT_MAX
622
if (is_positive(rate_max_rads)) {
623
desired_rate = constrain_float(desired_rate, -rate_max_rads, rate_max_rads);
624
}
625
626
// if acceleration limit is provided, ensure rate can be slowed to zero in time to stop at heading_rad (i.e. avoid overshoot)
627
if (is_positive(_steer_accel_max)) {
628
const float steer_accel_rate_max_rads = safe_sqrt(2.0 * fabsf(yaw_error) * radians(_steer_accel_max));
629
desired_rate = constrain_float(desired_rate, -steer_accel_rate_max_rads, steer_accel_rate_max_rads);
630
}
631
632
return desired_rate;
633
}
634
635
// return a steering servo output given a desired yaw rate in radians/sec.
636
// positive yaw is to the right
637
// return value is normally in range -1.0 to +1.0 but can be higher or lower
638
// also sets steering_limit_left and steering_limit_right flags
639
float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
640
{
641
// sanity check dt
642
dt = constrain_float(dt, 0.0f, 1.0f);
643
644
// update steering limit flags used by higher level controllers (e.g. position controller)
645
_steering_limit_left = motor_limit_left;
646
_steering_limit_right = motor_limit_right;
647
648
// if not called recently, reset input filter and desired turn rate to actual turn rate (used for accel limiting)
649
const uint32_t now = AP_HAL::millis();
650
if ((_steer_turn_last_ms == 0) || ((now - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
651
_steer_rate_pid.reset_filter();
652
_steer_rate_pid.reset_I();
653
_desired_turn_rate = AP::ahrs().get_yaw_rate_earth();
654
}
655
_steer_turn_last_ms = now;
656
657
// acceleration limit desired turn rate
658
if (is_positive(_steer_accel_max)) {
659
const float change_max = radians(_steer_accel_max) * dt;
660
if (desired_rate <= _desired_turn_rate - change_max) {
661
_steering_limit_left = true;
662
}
663
if (desired_rate >= _desired_turn_rate + change_max) {
664
_steering_limit_right = true;
665
}
666
desired_rate = constrain_float(desired_rate, _desired_turn_rate - change_max, _desired_turn_rate + change_max);
667
}
668
_desired_turn_rate = desired_rate;
669
670
// rate limit desired turn rate
671
if (is_positive(_steer_rate_max)) {
672
const float steer_rate_max_rad = radians(_steer_rate_max);
673
if (_desired_turn_rate <= -steer_rate_max_rad) {
674
_steering_limit_left = true;
675
}
676
if (_desired_turn_rate >= steer_rate_max_rad) {
677
_steering_limit_right = true;
678
}
679
_desired_turn_rate = constrain_float(_desired_turn_rate, -steer_rate_max_rad, steer_rate_max_rad);
680
}
681
682
// G limit based on speed
683
float speed;
684
if (get_forward_speed(speed)) {
685
// do not limit to less than 1 deg/s
686
const float turn_rate_max = MAX(get_turn_rate_from_lat_accel(get_turn_lat_accel_max(), fabsf(speed)), radians(1.0f));
687
if (_desired_turn_rate <= -turn_rate_max) {
688
_steering_limit_left = true;
689
}
690
if (_desired_turn_rate >= turn_rate_max) {
691
_steering_limit_right = true;
692
}
693
_desired_turn_rate = constrain_float(_desired_turn_rate, -turn_rate_max, turn_rate_max);
694
}
695
696
// update pid to calculate output to motors
697
float output = _steer_rate_pid.update_all(_desired_turn_rate, AP::ahrs().get_yaw_rate_earth(), dt, (motor_limit_left || motor_limit_right));
698
output += _steer_rate_pid.get_ff();
699
// constrain and return final output
700
return output;
701
}
702
703
// get latest desired turn rate in rad/sec (recorded during calls to get_steering_out_rate)
704
float AR_AttitudeControl::get_desired_turn_rate() const
705
{
706
// return zero if no recent calls to turn rate controller
707
if ((_steer_turn_last_ms == 0) || ((AP_HAL::millis() - _steer_turn_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
708
return 0.0f;
709
}
710
return _desired_turn_rate;
711
}
712
713
// get latest desired lateral acceleration in m/s/s (recorded during calls to get_steering_out_lat_accel)
714
float AR_AttitudeControl::get_desired_lat_accel() const
715
{
716
// return zero if no recent calls to lateral acceleration controller
717
if ((_steer_lat_accel_last_ms == 0) || ((AP_HAL::millis() - _steer_lat_accel_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
718
return 0.0f;
719
}
720
return _desired_lat_accel;
721
}
722
723
// get actual lateral acceleration in m/s/s. returns true on success
724
bool AR_AttitudeControl::get_lat_accel(float &lat_accel) const
725
{
726
float speed;
727
if (!get_forward_speed(speed)) {
728
return false;
729
}
730
lat_accel = speed * AP::ahrs().get_yaw_rate_earth();
731
return true;
732
}
733
734
// calculate the turn rate in rad/sec given a lateral acceleration (in m/s/s) and speed (in m/s)
735
float AR_AttitudeControl::get_turn_rate_from_lat_accel(float lat_accel, float speed) const
736
{
737
// enforce minimum speed to stop oscillations when first starting to move
738
if (fabsf(speed) < AR_ATTCONTROL_STEER_SPEED_MIN) {
739
if (is_negative(speed)) {
740
speed = -AR_ATTCONTROL_STEER_SPEED_MIN;
741
} else {
742
speed = AR_ATTCONTROL_STEER_SPEED_MIN;
743
}
744
}
745
746
return lat_accel / speed;
747
}
748
749
// return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
750
// motor_limit should be true if motors have hit their upper or lower limits
751
// cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
752
float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
753
{
754
// sanity check dt
755
dt = constrain_float(dt, 0.0f, 1.0f);
756
757
// get speed forward
758
float speed;
759
if (!get_forward_speed(speed)) {
760
// we expect caller will not try to control heading using rate control without a valid speed estimate
761
// on failure to get speed we do not attempt to steer
762
return 0.0f;
763
}
764
765
// if not called recently, reset input filter and desired speed to actual speed (used for accel limiting)
766
if (!speed_control_active()) {
767
_throttle_speed_pid.reset_filter();
768
_throttle_speed_pid.reset_I();
769
_desired_speed = speed;
770
}
771
_speed_last_ms = AP_HAL::millis();
772
773
// acceleration limit desired speed
774
_desired_speed = get_desired_speed_accel_limited(desired_speed, dt);
775
776
// calculate base throttle (protect against divide by zero)
777
float throttle_base = 0.0f;
778
if (is_positive(cruise_speed) && is_positive(cruise_throttle)) {
779
throttle_base = _desired_speed * (cruise_throttle / cruise_speed);
780
}
781
782
// calculate final output
783
float throttle_out = _throttle_speed_pid.update_all(_desired_speed, speed, dt, (motor_limit_low || motor_limit_high || _throttle_limit_low || _throttle_limit_high));
784
throttle_out += _throttle_speed_pid.get_ff();
785
throttle_out += throttle_base;
786
787
// update PID info for reporting purposes
788
_throttle_speed_pid_info = _throttle_speed_pid.get_pid_info();
789
_throttle_speed_pid_info.FF += throttle_base;
790
791
// clear local limit flags used to stop i-term build-up as we stop reversed outputs going to motors
792
_throttle_limit_low = false;
793
_throttle_limit_high = false;
794
795
// protect against reverse output being sent to the motors unless braking has been enabled
796
if (!_brake_enable) {
797
// if both desired speed and actual speed are positive, do not allow negative values
798
if ((_desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
799
throttle_out = 0.0f;
800
_throttle_limit_low = true;
801
} else if ((_desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
802
throttle_out = 0.0f;
803
_throttle_limit_high = true;
804
}
805
}
806
807
// final output throttle in range -1 to 1
808
return throttle_out;
809
}
810
811
// return a throttle output from -1 to +1 to perform a controlled stop. returns true once the vehicle has stopped
812
float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
813
{
814
// get current system time
815
const uint32_t now = AP_HAL::millis();
816
817
// if we were stopped in the last 300ms, assume we are still stopped
818
bool _stopped = (_stop_last_ms != 0) && (now - _stop_last_ms) < 300;
819
820
// get deceleration limited speed
821
float desired_speed_limited = get_desired_speed_accel_limited(0.0f, dt);
822
823
// get speed forward
824
float speed;
825
if (!get_forward_speed(speed)) {
826
// could not get speed so assume stopped
827
_stopped = true;
828
} else {
829
// if desired speed is zero and vehicle drops below _stop_speed consider it stopped
830
if (is_zero(desired_speed_limited) && fabsf(speed) <= fabsf(_stop_speed)) {
831
_stopped = true;
832
}
833
}
834
835
// set stopped status for caller
836
stopped = _stopped;
837
838
// if stopped return zero
839
if (stopped) {
840
// update last time we thought we were stopped
841
_stop_last_ms = now;
842
// set last time speed controller was run so accelerations are limited
843
_speed_last_ms = now;
844
// reset filters and I-term
845
_throttle_speed_pid.reset_filter();
846
_throttle_speed_pid.reset_I();
847
// ensure desired speed is zero
848
_desired_speed = 0.0f;
849
return 0.0f;
850
}
851
852
// clear stopped system time
853
_stop_last_ms = 0;
854
// run speed controller to bring vehicle to stop
855
return get_throttle_out_speed(desired_speed_limited, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle, dt);
856
}
857
858
// balancebot pitch to throttle controller
859
// returns a throttle output from -1 to +1 given a desired pitch angle (in radians)
860
// pitch_max should be the user defined max pitch angle (in radians)
861
// motor_limit should be true if the motors have hit their upper or lower limit
862
float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float pitch_max, bool motor_limit, float dt)
863
{
864
// sanity check dt
865
dt = constrain_float(dt, 0.0f, 1.0f);
866
867
// if not called recently, reset input filter
868
const uint32_t now = AP_HAL::millis();
869
if ((_balance_last_ms == 0) || ((now - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
870
_pitch_to_throttle_pid.reset_filter();
871
_pitch_to_throttle_pid.reset_I();
872
_pitch_limit_low = -pitch_max;
873
_pitch_limit_high = pitch_max;
874
}
875
_balance_last_ms = now;
876
877
// limit desired pitch to protect against falling
878
const bool pitch_limit_active = (_pitch_limit_tc >= 0.01) && (_pitch_limit_throttle_thresh > 0);
879
if (pitch_limit_active) {
880
desired_pitch = constrain_float(desired_pitch, _pitch_limit_low, _pitch_limit_high);
881
_pitch_limited = (desired_pitch <= _pitch_limit_low || desired_pitch >= _pitch_limit_high);
882
} else {
883
_pitch_limited = false;
884
}
885
886
// initialise output to feed forward from current pitch angle
887
const float pitch_rad = AP::ahrs().get_pitch();
888
float output = sinf(pitch_rad) * _pitch_to_throttle_ff;
889
890
// add regular PID control
891
output += _pitch_to_throttle_pid.update_all(desired_pitch, pitch_rad, dt, motor_limit);
892
output += _pitch_to_throttle_pid.get_ff();
893
894
// update pitch limits for next iteration
895
// note: pitch is positive when leaning backwards, negative when leaning forward
896
if (pitch_limit_active) {
897
const float pitch_limit_incr = 1.0/_pitch_limit_tc * dt * pitch_max;
898
const float pitch_relax_incr = pitch_limit_incr * AR_ATTCONTROL_PITCH_RELAX_RATIO;
899
if (output <= -_pitch_limit_throttle_thresh) {
900
// very low negative throttle output means we must lower pitch_high (e.g. reduce leaning backwards)
901
_pitch_limit_high = MAX(_pitch_limit_high - pitch_limit_incr, 0);
902
} else {
903
_pitch_limit_high = MIN(_pitch_limit_high + pitch_relax_incr, pitch_max);
904
}
905
if (output >= _pitch_limit_throttle_thresh) {
906
// very high positive throttle output means we must raise pitch_low (reduce leaning forwards)
907
_pitch_limit_low = MIN(_pitch_limit_low + pitch_limit_incr, 0);
908
} else {
909
_pitch_limit_low = MAX(_pitch_limit_low - pitch_relax_incr, -pitch_max);
910
}
911
}
912
913
// constrain and return final output
914
return output;
915
}
916
917
// get latest desired pitch in radians for reporting purposes
918
float AR_AttitudeControl::get_desired_pitch() const
919
{
920
// if not called recently, return 0
921
if ((_balance_last_ms == 0) || ((AP_HAL::millis() - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
922
return 0.0f;
923
}
924
925
return _pitch_to_throttle_pid.get_pid_info().target;
926
}
927
928
// Sailboat heel(roll) angle controller releases sail to keep at maximum heel angle
929
// but does not attempt to reach maximum heel angle, ie only lets sails out, does not pull them in
930
float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt)
931
{
932
// sanity check dt
933
dt = constrain_float(dt, 0.0f, 1.0f);
934
935
// if not called recently, reset input filter
936
const uint32_t now = AP_HAL::millis();
937
if ((_heel_controller_last_ms == 0) || ((now - _heel_controller_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
938
_sailboat_heel_pid.reset_filter();
939
_sailboat_heel_pid.reset_I();
940
}
941
_heel_controller_last_ms = now;
942
943
_sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().get_roll()), dt);
944
945
// get feed-forward
946
const float ff = _sailboat_heel_pid.get_ff();
947
948
// get p, constrain to be zero or negative
949
float p = _sailboat_heel_pid.get_p();
950
if (is_positive(p)) {
951
p = 0.0f;
952
}
953
954
// get i, constrain to be zero or negative
955
float i = _sailboat_heel_pid.get_i();
956
if (is_positive(i)) {
957
i = 0.0f;
958
_sailboat_heel_pid.reset_I();
959
}
960
961
// get d
962
const float d = _sailboat_heel_pid.get_d();
963
964
// constrain and return final output
965
return (ff + p + i + d) * -1.0f;
966
}
967
968
// get the slew rate value for speed and steering for oscillation detection in lua scripts
969
void AR_AttitudeControl::get_srate(float &steering_srate, float &speed_srate)
970
{
971
steering_srate = get_steering_rate_pid().get_pid_info().slew_rate;
972
speed_srate = _throttle_speed_pid_info.slew_rate;
973
}
974
975
// get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
976
bool AR_AttitudeControl::get_forward_speed(float &speed) const
977
{
978
Vector3f velocity;
979
const AP_AHRS &_ahrs = AP::ahrs();
980
if (!_ahrs.get_velocity_NED(velocity)) {
981
// use less accurate GPS, assuming entire length is along forward/back axis of vehicle
982
if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
983
if (abs(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) {
984
speed = AP::gps().ground_speed();
985
} else {
986
speed = -AP::gps().ground_speed();
987
}
988
return true;
989
} else {
990
return false;
991
}
992
}
993
// calculate forward speed velocity into body frame
994
speed = velocity.x*_ahrs.cos_yaw() + velocity.y*_ahrs.sin_yaw();
995
return true;
996
}
997
998
float AR_AttitudeControl::get_decel_max() const
999
{
1000
if (is_positive(_throttle_decel_max)) {
1001
return _throttle_decel_max;
1002
} else {
1003
return _throttle_accel_max;
1004
}
1005
}
1006
1007
// check if speed controller active
1008
bool AR_AttitudeControl::speed_control_active() const
1009
{
1010
// active if there have been recent calls to speed controller
1011
if ((_speed_last_ms == 0) || ((AP_HAL::millis() - _speed_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) {
1012
return false;
1013
}
1014
return true;
1015
}
1016
1017
// get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
1018
float AR_AttitudeControl::get_desired_speed() const
1019
{
1020
// return zero if no recent calls to speed controller
1021
if (!speed_control_active()) {
1022
return 0.0f;
1023
}
1024
return _desired_speed;
1025
}
1026
1027
// get acceleration limited desired speed
1028
float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, float dt) const
1029
{
1030
// return input value if no recent calls to speed controller
1031
// apply no limiting when ATC_ACCEL_MAX is set to zero
1032
if (!speed_control_active() || !is_positive(_throttle_accel_max)) {
1033
return desired_speed;
1034
}
1035
1036
// sanity check dt
1037
dt = constrain_float(dt, 0.0f, 1.0f);
1038
1039
// use previous desired speed as basis for accel limiting
1040
float speed_prev = _desired_speed;
1041
1042
// if no recent calls to speed controller limit based on current speed
1043
if (!speed_control_active()) {
1044
get_forward_speed(speed_prev);
1045
}
1046
1047
// acceleration limit desired speed
1048
float speed_change_max;
1049
if (fabsf(desired_speed) < fabsf(_desired_speed) && is_positive(_throttle_decel_max)) {
1050
speed_change_max = _throttle_decel_max * dt;
1051
} else {
1052
speed_change_max = _throttle_accel_max * dt;
1053
}
1054
return constrain_float(desired_speed, speed_prev - speed_change_max, speed_prev + speed_change_max);
1055
}
1056
1057
// get minimum stopping distance (in meters) given a speed (in m/s)
1058
float AR_AttitudeControl::get_stopping_distance(float speed) const
1059
{
1060
// get maximum vehicle deceleration
1061
const float decel_max = get_decel_max();
1062
1063
if ((decel_max <= 0.0f) || is_zero(speed)) {
1064
return 0.0f;
1065
}
1066
1067
// assume linear deceleration
1068
return 0.5f * sq(speed) / decel_max;
1069
}
1070
1071
// relax I terms of throttle and steering controllers
1072
void AR_AttitudeControl::relax_I()
1073
{
1074
_steer_rate_pid.reset_I();
1075
_throttle_speed_pid.reset_I();
1076
_pitch_to_throttle_pid.reset_I();
1077
}
1078
1079
void AR_AttitudeControl::set_notch_sample_rate(float sample_rate)
1080
{
1081
#if AP_FILTER_ENABLED
1082
_steer_rate_pid.set_notch_sample_rate(sample_rate);
1083
_throttle_speed_pid.set_notch_sample_rate(sample_rate);
1084
_pitch_to_throttle_pid.set_notch_sample_rate(sample_rate);
1085
#endif
1086
}
1087
1088