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/AP_AutoTune.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
/**
17
The strategy for roll/pitch autotune is to give the user a AUTOTUNE
18
flight mode which behaves just like FBWA, but does automatic
19
tuning.
20
*/
21
22
#include "AP_AutoTune.h"
23
24
#include <AP_Common/AP_Common.h>
25
#include <AP_HAL/AP_HAL.h>
26
#include <AP_Logger/AP_Logger.h>
27
#include <AP_Math/AP_Math.h>
28
#include <AC_PID/AC_PID.h>
29
#include <AP_Scheduler/AP_Scheduler.h>
30
#include <GCS_MAVLink/GCS.h>
31
#include <AP_InertialSensor/AP_InertialSensor.h>
32
33
extern const AP_HAL::HAL& hal;
34
35
// step size for changing FF gains, percentage
36
#define AUTOTUNE_INCREASE_FF_STEP 12
37
#define AUTOTUNE_DECREASE_FF_STEP 15
38
39
// limits on IMAX
40
#define AUTOTUNE_MIN_IMAX 0.4
41
#define AUTOTUNE_MAX_IMAX 0.9
42
43
// ratio of I to P
44
#define AUTOTUNE_I_RATIO 0.75
45
46
// time constant of rate trim loop
47
#define TRIM_TCONST 1.0f
48
49
// constructor
50
AP_AutoTune::AP_AutoTune(ATGains &_gains, ATType _type,
51
const AP_FixedWing &parms,
52
AC_PID &_rpid) :
53
current(_gains),
54
rpid(_rpid),
55
type(_type),
56
aparm(parms),
57
ff_filter(2)
58
{}
59
60
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
61
#include <stdio.h>
62
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
63
#else
64
# define Debug(fmt, args ...)
65
#endif
66
67
/*
68
auto-tuning table. This table gives the starting values for key
69
tuning parameters based on a user chosen AUTOTUNE_LEVEL parameter
70
from 1 to 10. Level 1 is a very soft tune. Level 10 is a very
71
aggressive tune.
72
Level 0 means use the existing RMAX and TCONST parameters
73
*/
74
static const struct {
75
float tau;
76
float rmax;
77
} tuning_table[] = {
78
{ 1.00, 20 }, // level 1
79
{ 0.90, 30 }, // level 2
80
{ 0.80, 40 }, // level 3
81
{ 0.70, 50 }, // level 4
82
{ 0.60, 60 }, // level 5
83
{ 0.50, 75 }, // level 6
84
{ 0.30, 90 }, // level 7
85
{ 0.2, 120 }, // level 8
86
{ 0.15, 160 }, // level 9
87
{ 0.1, 210 }, // level 10
88
{ 0.1, 300 }, // (yes, it goes to 11)
89
};
90
91
/*
92
start an autotune session
93
*/
94
void AP_AutoTune::start(void)
95
{
96
running = true;
97
state = ATState::IDLE;
98
99
current = restore = last_save = get_gains();
100
101
// do first update of rmax and tau now
102
update_rmax();
103
104
dt = AP::scheduler().get_loop_period_s();
105
106
rpid.kIMAX().set(constrain_float(rpid.kIMAX(), AUTOTUNE_MIN_IMAX, AUTOTUNE_MAX_IMAX));
107
108
// use 0.75Hz filters on the actuator, rate and target to reduce impact of noise
109
actuator_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);
110
rate_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 0.75);
111
112
// target filter is a bit broader
113
target_filter.set_cutoff_frequency(AP::scheduler().get_loop_rate_hz(), 4);
114
115
ff_filter.reset();
116
actuator_filter.reset();
117
rate_filter.reset();
118
D_limit = 0;
119
P_limit = 0;
120
ff_count = 0;
121
D_set_ms = 0;
122
P_set_ms = 0;
123
done_count = 0;
124
125
if (!is_positive(rpid.slew_limit())) {
126
// we must have a slew limit, default to 150 deg/s
127
rpid.slew_limit().set_and_save(150);
128
}
129
130
if (current.FF < 0.01) {
131
// don't allow for zero FF
132
current.FF = 0.01;
133
rpid.ff().set(current.FF);
134
}
135
136
Debug("START FF -> %.3f\n", rpid.ff().get());
137
}
138
139
/*
140
called when we change state to see if we should change gains
141
*/
142
void AP_AutoTune::stop(void)
143
{
144
if (running) {
145
running = false;
146
if (is_positive(D_limit) && is_positive(P_limit)) {
147
save_gains();
148
} else {
149
restore_gains();
150
}
151
}
152
}
153
154
const char *AP_AutoTune::axis_string(void) const
155
{
156
switch (type) {
157
case AUTOTUNE_ROLL:
158
return "Roll";
159
case AUTOTUNE_PITCH:
160
return "Pitch";
161
case AUTOTUNE_YAW:
162
return "Yaw";
163
}
164
return "";
165
}
166
167
/*
168
one update cycle of the autotuner
169
*/
170
void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
171
{
172
if (!running) {
173
return;
174
}
175
176
// see what state we are in
177
ATState new_state = state;
178
const float desired_rate = target_filter.apply(pinfo.target);
179
180
// filter actuator without I term so we can take ratios without
181
// accounting for trim offsets. We first need to include the I and
182
// clip to 45 degrees to get the right value of the real surface
183
const float clipped_actuator = constrain_float(pinfo.FF + pinfo.P + pinfo.D + pinfo.DFF + pinfo.I, -45, 45) - pinfo.I;
184
const float actuator = actuator_filter.apply(clipped_actuator);
185
const float actual_rate = rate_filter.apply(pinfo.actual);
186
187
max_actuator = MAX(max_actuator, actuator);
188
min_actuator = MIN(min_actuator, actuator);
189
max_rate = MAX(max_rate, actual_rate);
190
min_rate = MIN(min_rate, actual_rate);
191
max_target = MAX(max_target, desired_rate);
192
min_target = MIN(min_target, desired_rate);
193
max_P = MAX(max_P, fabsf(pinfo.P));
194
max_D = MAX(max_D, fabsf(pinfo.D));
195
min_Dmod = MIN(min_Dmod, pinfo.Dmod);
196
max_Dmod = MAX(max_Dmod, pinfo.Dmod);
197
198
// update the P and D slew rates, using P and D values from before Dmod was applied
199
const float slew_limit_scale = 45.0 / degrees(1);
200
slew_limit_max = rpid.slew_limit();
201
slew_limit_tau = 1.0;
202
slew_limiter_P.modifier((pinfo.P/pinfo.Dmod)*slew_limit_scale, dt);
203
slew_limiter_D.modifier((pinfo.D/pinfo.Dmod)*slew_limit_scale, dt);
204
205
// remember maximum slew rates for this cycle
206
max_SRate_P = MAX(max_SRate_P, slew_limiter_P.get_slew_rate());
207
max_SRate_D = MAX(max_SRate_D, slew_limiter_D.get_slew_rate());
208
209
float att_limit_deg = 0;
210
switch (type) {
211
case AUTOTUNE_ROLL:
212
att_limit_deg = aparm.roll_limit;
213
break;
214
case AUTOTUNE_PITCH:
215
att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;
216
break;
217
case AUTOTUNE_YAW:
218
// arbitrary value for yaw angle
219
att_limit_deg = 20;
220
break;
221
}
222
223
224
// thresholds for when we consider an event to start and end
225
const float rate_threshold1 = 0.4 * MIN(att_limit_deg / current.tau.get(), current.rmax_pos);
226
const float rate_threshold2 = 0.25 * rate_threshold1;
227
bool in_att_demand = fabsf(angle_err_deg) >= 0.3 * att_limit_deg;
228
229
switch (state) {
230
case ATState::IDLE:
231
if (desired_rate > rate_threshold1 && in_att_demand) {
232
new_state = ATState::DEMAND_POS;
233
} else if (desired_rate < -rate_threshold1 && in_att_demand) {
234
new_state = ATState::DEMAND_NEG;
235
}
236
break;
237
case ATState::DEMAND_POS:
238
if (desired_rate < rate_threshold2) {
239
new_state = ATState::IDLE;
240
}
241
break;
242
case ATState::DEMAND_NEG:
243
if (desired_rate > -rate_threshold2) {
244
new_state = ATState::IDLE;
245
}
246
break;
247
}
248
249
const uint32_t now = AP_HAL::millis();
250
251
#if HAL_LOGGING_ENABLED
252
if (now - last_log_ms >= 40) {
253
// log at 25Hz
254
const struct log_ATRP pkt {
255
LOG_PACKET_HEADER_INIT(LOG_ATRP_MSG),
256
time_us : AP_HAL::micros64(),
257
type : uint8_t(type),
258
state: uint8_t(new_state),
259
actuator : actuator,
260
P_slew : max_SRate_P,
261
D_slew : max_SRate_D,
262
FF_single: FF_single,
263
FF: current.FF,
264
P: current.P,
265
I: current.I,
266
D: current.D,
267
action: uint8_t(action),
268
rmax: float(current.rmax_pos.get()),
269
tau: current.tau.get()
270
};
271
AP::logger().WriteBlock(&pkt, sizeof(pkt));
272
last_log_ms = now;
273
}
274
#endif
275
276
if (new_state == state) {
277
if (state == ATState::IDLE &&
278
now - state_enter_ms > 500 &&
279
max_Dmod < 0.9) {
280
// we've been oscillating while idle, reduce P or D
281
const float slew_sum = max_SRate_P + max_SRate_D;
282
const float gain_mul = 0.5;
283
current.P *= linear_interpolate(gain_mul, 1.0,
284
max_SRate_P,
285
slew_sum, 0);
286
current.D *= linear_interpolate(gain_mul, 1.0,
287
max_SRate_D,
288
slew_sum, 0);
289
rpid.kP().set(current.P);
290
rpid.kD().set(current.D);
291
action = Action::IDLE_LOWER_PD;
292
P_limit = MIN(P_limit, current.P);
293
D_limit = MIN(D_limit, current.D);
294
state_change(state);
295
}
296
return;
297
}
298
299
if (new_state != ATState::IDLE) {
300
// starting an event
301
min_actuator = max_actuator = min_rate = max_rate = 0;
302
state_enter_ms = now;
303
state = new_state;
304
return;
305
}
306
307
if ((state == ATState::DEMAND_POS && max_rate < 0.01 * current.rmax_pos) ||
308
(state == ATState::DEMAND_NEG && min_rate > -0.01 * current.rmax_neg)) {
309
// we didn't get enough rate
310
action = Action::LOW_RATE;
311
state_change(ATState::IDLE);
312
return;
313
}
314
315
if (now - state_enter_ms < 100) {
316
// not long enough sample
317
action = Action::SHORT;
318
state_change(ATState::IDLE);
319
return;
320
}
321
322
// we've finished an event. calculate the single-event FF value
323
if (state == ATState::DEMAND_POS) {
324
FF_single = max_actuator / (max_rate * scaler);
325
} else {
326
FF_single = min_actuator / (min_rate * scaler);
327
}
328
329
// apply median filter
330
float FF = ff_filter.apply(FF_single);
331
ff_count++;
332
333
const float old_FF = rpid.ff();
334
335
// limit size of change in FF
336
FF = constrain_float(FF,
337
old_FF*(1-AUTOTUNE_DECREASE_FF_STEP*0.01),
338
old_FF*(1+AUTOTUNE_INCREASE_FF_STEP*0.01));
339
340
// adjust P and D
341
float D = rpid.kD();
342
float P = rpid.kP();
343
344
if (ff_count == 1) {
345
// apply minimum D and P values
346
D = MAX(D, 0.0005);
347
P = MAX(P, 0.01);
348
} else if (ff_count == 4) {
349
// we got a good ff estimate, halve P ready to start raising D
350
P *= 0.5;
351
}
352
353
// see if the slew limiter kicked in
354
if (min_Dmod < 1.0 && !is_positive(D_limit)) {
355
// oscillation, without D_limit set
356
if (max_P > 0.5 * max_D) {
357
// lower P and D to get us to a non-oscillating state
358
P *= 0.35;
359
D *= 0.75;
360
action = Action::LOWER_PD;
361
} else {
362
// set D limit to 30% of current D, remember D limit and start to work on P
363
D *= 0.3;
364
D_limit = D;
365
D_set_ms = now;
366
action = Action::LOWER_D;
367
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);
368
}
369
} else if (min_Dmod < 1.0) {
370
// oscillation, with D_limit set
371
if (now - D_set_ms > 2000) {
372
// leave 2s for Dmod to settle after lowering D
373
if (max_D > 0.8 * max_P) {
374
// lower D limit some more
375
D *= 0.35;
376
D_limit = D;
377
D_set_ms = now;
378
action = Action::LOWER_D;
379
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sD: %.4f", axis_string(), D_limit);
380
done_count = 0;
381
} else if (now - P_set_ms > 2500) {
382
if (is_positive(P_limit)) {
383
// if we've already got a P estimate then don't
384
// reduce as quickly, stopping small spikes at the
385
// later part of the tune from giving us a very
386
// low P gain
387
P *= 0.7;
388
} else {
389
P *= 0.35;
390
}
391
P_limit = P;
392
P_set_ms = now;
393
action = Action::LOWER_P;
394
done_count = 0;
395
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%sP: %.4f", axis_string(), P_limit);
396
}
397
}
398
} else if (ff_count < 4) {
399
// we don't have a good FF estimate yet, keep going
400
401
} else if (!is_positive(D_limit)) {
402
/* we haven't detected D oscillation yet, keep raising D */
403
D *= 1.3;
404
action = Action::RAISE_D;
405
} else if (!is_positive(P_limit)) {
406
/* not oscillating, increase P gain */
407
P *= 1.3;
408
action = Action::RAISE_PD;
409
} else {
410
// after getting P_limit we consider the tune done when we
411
// have done 3 cycles without reducing P
412
if (done_count < 3) {
413
if (++done_count == 3) {
414
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s: Finished", axis_string());
415
save_gains();
416
}
417
}
418
}
419
420
rpid.ff().set(FF);
421
rpid.kP().set(P);
422
rpid.kD().set(D);
423
if (type == AUTOTUNE_ROLL) { // for roll set I = smaller of FF or P
424
rpid.kI().set(MIN(P, (FF / TRIM_TCONST)));
425
} else { // for pitch/yaw naturally damped axes) set I usually = FF to get 1 sec I closure
426
rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));
427
}
428
429
// setup filters to be suitable for time constant and gyro filter
430
// filtering T can prevent P/D oscillation being seen, so allow the
431
// user to switch it off
432
if (!has_option(DISABLE_FLTT_UPDATE)) {
433
rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));
434
}
435
rpid.filt_E_hz().set(0);
436
// filtering D at the same level as VTOL can allow unwanted oscillations to be seen,
437
// so allow the user to switch it off and select their own (usually lower) value
438
if (!has_option(DISABLE_FLTD_UPDATE)) {
439
rpid.filt_D_hz().set(AP::ins().get_gyro_filter_hz()*0.5);
440
}
441
442
current.FF = FF;
443
current.P = P;
444
current.I = rpid.kI().get();
445
current.D = D;
446
447
Debug("FPID=(%.3f, %.3f, %.3f, %.3f) Dmod=%.2f\n",
448
rpid.ff().get(),
449
rpid.kP().get(),
450
rpid.kI().get(),
451
rpid.kD().get(),
452
min_Dmod);
453
454
// move rmax and tau towards target
455
update_rmax();
456
457
state_change(new_state);
458
}
459
460
/*
461
record a state change
462
*/
463
void AP_AutoTune::state_change(ATState new_state)
464
{
465
min_Dmod = 1;
466
max_Dmod = 0;
467
max_SRate_P = 1;
468
max_SRate_D = 1;
469
max_P = max_D = 0;
470
state = new_state;
471
state_enter_ms = AP_HAL::millis();
472
}
473
474
/*
475
save a float if it has changed
476
*/
477
void AP_AutoTune::save_float_if_changed(AP_Float &v, float old_value)
478
{
479
if (!is_equal(old_value, v.get())) {
480
v.save();
481
}
482
}
483
484
/*
485
save a int16_t if it has changed
486
*/
487
void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t old_value)
488
{
489
if (old_value != v.get()) {
490
v.save();
491
}
492
}
493
494
495
/*
496
save a set of gains
497
*/
498
void AP_AutoTune::save_gains(void)
499
{
500
const auto &v = last_save;
501
save_float_if_changed(current.tau, v.tau);
502
save_int16_if_changed(current.rmax_pos, v.rmax_pos);
503
save_int16_if_changed(current.rmax_neg, v.rmax_neg);
504
save_float_if_changed(rpid.ff(), v.FF);
505
save_float_if_changed(rpid.kP(), v.P);
506
save_float_if_changed(rpid.kI(), v.I);
507
save_float_if_changed(rpid.kD(), v.D);
508
save_float_if_changed(rpid.kIMAX(), v.IMAX);
509
save_float_if_changed(rpid.filt_T_hz(), v.flt_T);
510
save_float_if_changed(rpid.filt_E_hz(), v.flt_E);
511
save_float_if_changed(rpid.filt_D_hz(), v.flt_D);
512
last_save = get_gains();
513
}
514
515
/*
516
get gains with PID components
517
*/
518
AP_AutoTune::ATGains AP_AutoTune::get_gains(void)
519
{
520
ATGains ret = current;
521
ret.FF = rpid.ff();
522
ret.P = rpid.kP();
523
ret.I = rpid.kI();
524
ret.D = rpid.kD();
525
ret.IMAX = rpid.kIMAX();
526
ret.flt_T = rpid.filt_T_hz();
527
ret.flt_E = rpid.filt_E_hz();
528
ret.flt_D = rpid.filt_D_hz();
529
return ret;
530
}
531
532
/*
533
set gains with PID components
534
*/
535
void AP_AutoTune::restore_gains(void)
536
{
537
current = restore;
538
rpid.ff().set(restore.FF);
539
rpid.kP().set(restore.P);
540
rpid.kI().set(restore.I);
541
rpid.kD().set(restore.D);
542
rpid.kIMAX().set(restore.IMAX);
543
rpid.filt_T_hz().set(restore.flt_T);
544
rpid.filt_E_hz().set(restore.flt_E);
545
rpid.filt_D_hz().set(restore.flt_D);
546
}
547
548
/*
549
update RMAX and TAU parameters on each step. We move them gradually
550
towards the target to allow for a user going straight to a level 10
551
tune while starting with a poorly tuned plane
552
*/
553
void AP_AutoTune::update_rmax(void)
554
{
555
uint8_t level = constrain_int32(aparm.autotune_level, 0, ARRAY_SIZE(tuning_table));
556
557
int16_t target_rmax;
558
float target_tau;
559
560
if (level == 0) {
561
// this level means to keep current values of RMAX and TCONST
562
target_rmax = constrain_float(current.rmax_pos, 20, 720);
563
target_tau = constrain_float(current.tau, 0.1, 2);
564
} else {
565
target_rmax = tuning_table[level-1].rmax;
566
target_tau = tuning_table[level-1].tau;
567
if (type == AUTOTUNE_PITCH) {
568
// 50% longer time constant on pitch
569
target_tau *= 1.5;
570
}
571
}
572
573
if (level > 0 && is_positive(current.FF)) {
574
const float invtau = ((1.0f / target_tau) + (current.I / current.FF));
575
if (is_positive(invtau)) {
576
target_tau = MAX(target_tau,1.0f / invtau);
577
}
578
}
579
580
if (current.rmax_pos == 0) {
581
// conservative initial value
582
current.rmax_pos.set(75);
583
}
584
// move RMAX by 20 deg/s per step
585
current.rmax_pos.set(constrain_int32(target_rmax,
586
current.rmax_pos.get()-20,
587
current.rmax_pos.get()+20));
588
589
if (level != 0 || current.rmax_neg.get() == 0) {
590
current.rmax_neg.set(current.rmax_pos.get());
591
}
592
593
// move tau by max 15% per loop
594
current.tau.set(constrain_float(target_tau,
595
current.tau*0.85,
596
current.tau*1.15));
597
}
598
599