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/AC_AutoTune/AC_AutoTune_Multi.cpp
Views: 1798
1
#include "AC_AutoTune_config.h"
2
3
#if AC_AUTOTUNE_ENABLED
4
5
#include "AC_AutoTune_Multi.h"
6
7
#include <AP_Logger/AP_Logger.h>
8
#include <AP_Scheduler/AP_Scheduler.h>
9
#include <GCS_MAVLink/GCS.h>
10
11
/*
12
* autotune support for multicopters
13
*
14
*
15
* Instructions:
16
* 1) Set up one flight mode switch position to be AltHold.
17
* 2) Set the Ch7 Opt or Ch8 Opt to AutoTune to allow you to turn the auto tuning on/off with the ch7 or ch8 switch.
18
* 3) Ensure the ch7 or ch8 switch is in the LOW position.
19
* 4) Wait for a calm day and go to a large open area.
20
* 5) Take off and put the vehicle into AltHold mode at a comfortable altitude.
21
* 6) Set the ch7/ch8 switch to the HIGH position to engage auto tuning:
22
* a) You will see it twitch about 20 degrees left and right for a few minutes, then it will repeat forward and back.
23
* b) Use the roll and pitch stick at any time to reposition the copter if it drifts away (it will use the original PID gains during repositioning and between tests).
24
* When you release the sticks it will continue auto tuning where it left off.
25
* c) Move the ch7/ch8 switch into the LOW position at any time to abandon the autotuning and return to the origin PIDs.
26
* d) Make sure that you do not have any trim set on your transmitter or the autotune may not get the signal that the sticks are centered.
27
* 7) When the tune completes the vehicle will change back to the original PID gains.
28
* 8) Put the ch7/ch8 switch into the LOW position then back to the HIGH position to test the tuned PID gains.
29
* 9) Put the ch7/ch8 switch into the LOW position to fly using the original PID gains.
30
* 10) If you are happy with the autotuned PID gains, leave the ch7/ch8 switch in the HIGH position, land and disarm to save the PIDs permanently.
31
* If you DO NOT like the new PIDS, switch ch7/ch8 LOW to return to the original PIDs. The gains will not be saved when you disarm
32
*
33
* What it's doing during each "twitch":
34
* a) invokes 90 deg/sec rate request
35
* b) records maximum "forward" roll rate and bounce back rate
36
* c) when copter reaches 20 degrees or 1 second has passed, it commands level
37
* d) tries to keep max rotation rate between 80% ~ 100% of requested rate (90deg/sec) by adjusting rate P
38
* e) increases rate D until the bounce back becomes greater than 10% of requested rate (90deg/sec)
39
* f) decreases rate D until the bounce back becomes less than 10% of requested rate (90deg/sec)
40
* g) increases rate P until the max rotate rate becomes greater than the request rate (90deg/sec)
41
* h) invokes a 20deg angle request on roll or pitch
42
* i) increases stab P until the maximum angle becomes greater than 110% of the requested angle (20deg)
43
* j) decreases stab P by 25%
44
*
45
*/
46
47
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 2000U // timeout for tuning mode's testing step
48
49
#define AUTOTUNE_RD_STEP 0.05 // minimum increment when increasing/decreasing Rate D term
50
#define AUTOTUNE_RP_STEP 0.05 // minimum increment when increasing/decreasing Rate P term
51
#define AUTOTUNE_SP_STEP 0.05 // minimum increment when increasing/decreasing Stab P term
52
#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1 // I is set 10x smaller than P during testing
53
#define AUTOTUNE_PI_RATIO_FINAL 1.0 // I is set 1x P after testing
54
#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1 // I is set 1x P after testing
55
#define AUTOTUNE_RD_MAX 0.200 // maximum Rate D value
56
#define AUTOTUNE_RLPF_MIN 1.0 // minimum Rate Yaw filter value
57
#define AUTOTUNE_RLPF_MAX 5.0 // maximum Rate Yaw filter value
58
#define AUTOTUNE_FLTE_MIN 2.5 // minimum Rate Yaw error filter value
59
#define AUTOTUNE_RP_MIN 0.01 // minimum Rate P value
60
#define AUTOTUNE_RP_MAX 2.0 // maximum Rate P value
61
#define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value
62
#define AUTOTUNE_SP_MIN 0.5 // maximum Stab P value
63
#define AUTOTUNE_RP_ACCEL_MIN 4000.0 // Minimum acceleration for Roll and Pitch
64
#define AUTOTUNE_Y_ACCEL_MIN 1000.0 // Minimum acceleration for Yaw
65
#define AUTOTUNE_Y_FILT_FREQ 10.0 // Autotune filter frequency when testing Yaw
66
#define AUTOTUNE_D_UP_DOWN_MARGIN 0.2 // The margin below the target that we tune D in
67
#define AUTOTUNE_RD_BACKOFF 1.0 // Rate D gains are reduced to 50% of their maximum value discovered during tuning
68
#define AUTOTUNE_RP_BACKOFF 1.0 // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning
69
#define AUTOTUNE_SP_BACKOFF 0.9 // Stab P gains are reduced to 90% of their maximum value discovered during tuning
70
#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0 // back off from maximum acceleration
71
#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0 // back off from maximum acceleration
72
73
// roll and pitch axes
74
#define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
75
#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target min roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
76
77
// yaw axis
78
#define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
79
#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step
80
81
#define AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE 1.0 / 2.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step
82
#define AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE 1.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step
83
#define AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE 1.0 / 3.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step
84
#define AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE 1.0 / 6.0 // minimum target angle, as a fraction of angle_max, during TESTING_RATE step that will cause us to move to next step
85
#define AUTOTUNE_ANGLE_ABORT_RP_SCALE 2.5 / 3.0 // maximum allowable angle during testing, as a fraction of angle_max
86
#define AUTOTUNE_ANGLE_MAX_Y_SCALE 1.0 // maximum allowable angle during testing, as a fraction of angle_max
87
#define AUTOTUNE_ANGLE_NEG_RP_SCALE 1.0 / 5.0 // maximum allowable angle during testing, as a fraction of angle_max
88
89
// second table of user settable parameters for quadplanes, this
90
// allows us to go beyond the 64 parameter limit
91
const AP_Param::GroupInfo AC_AutoTune_Multi::var_info[] = {
92
93
// @Param: AXES
94
// @DisplayName: Autotune axis bitmask
95
// @Description: 1-byte bitmap of axes to autotune
96
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:YawD
97
// @User: Standard
98
AP_GROUPINFO("AXES", 1, AC_AutoTune_Multi, axis_bitmask, 7), // AUTOTUNE_AXIS_BITMASK_DEFAULT
99
100
// @Param: AGGR
101
// @DisplayName: Autotune aggressiveness
102
// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
103
// @Range: 0.05 0.10
104
// @User: Standard
105
AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.075f),
106
107
// @Param: MIN_D
108
// @DisplayName: AutoTune minimum D
109
// @Description: Defines the minimum D gain
110
// @Range: 0.0001 0.005
111
// @User: Standard
112
AP_GROUPINFO("MIN_D", 3, AC_AutoTune_Multi, min_d, 0.0005f),
113
114
AP_GROUPEND
115
};
116
117
// constructor
118
AC_AutoTune_Multi::AC_AutoTune_Multi()
119
{
120
tune_seq[0] = TUNE_COMPLETE;
121
AP_Param::setup_object_defaults(this, var_info);
122
}
123
124
void AC_AutoTune_Multi::do_gcs_announcements()
125
{
126
const uint32_t now = AP_HAL::millis();
127
if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {
128
return;
129
}
130
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: %s %s %u%%", axis_string(), type_string(), (counter * (100/AUTOTUNE_SUCCESS_COUNT)));
131
announce_time = now;
132
}
133
134
void AC_AutoTune_Multi::test_init()
135
{
136
twitch_test_init();
137
}
138
139
void AC_AutoTune_Multi::test_run(AxisType test_axis, const float dir_sign)
140
{
141
twitch_test_run(test_axis, dir_sign);
142
}
143
144
// backup_gains_and_initialise - store current gains as originals
145
// called before tuning starts to backup original gains
146
void AC_AutoTune_Multi::backup_gains_and_initialise()
147
{
148
AC_AutoTune::backup_gains_and_initialise();
149
150
aggressiveness.set(constrain_float(aggressiveness, 0.05, 0.2));
151
152
orig_bf_feedforward = attitude_control->get_bf_feedforward();
153
154
// backup original pids and initialise tuned pid values
155
orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
156
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
157
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
158
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
159
orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();
160
orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz();
161
orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit();
162
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
163
orig_roll_accel = attitude_control->get_accel_roll_max_cdss();
164
tune_roll_rp = attitude_control->get_rate_roll_pid().kP();
165
tune_roll_rd = attitude_control->get_rate_roll_pid().kD();
166
tune_roll_sp = attitude_control->get_angle_roll_p().kP();
167
tune_roll_accel = attitude_control->get_accel_roll_max_cdss();
168
169
orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
170
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
171
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
172
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
173
orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();
174
orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz();
175
orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit();
176
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
177
orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
178
tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
179
tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
180
tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();
181
tune_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
182
183
orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
184
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
185
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
186
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
187
orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();
188
orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz();
189
orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit();
190
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
191
orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
192
orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
193
tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
194
tune_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
195
tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
196
if (yaw_d_enabled() && is_zero(tune_yaw_rd)) {
197
tune_yaw_rd = min_d;
198
}
199
if (yaw_enabled() && is_zero(tune_yaw_rLPF)) {
200
tune_yaw_rLPF = AUTOTUNE_FLTE_MIN;
201
}
202
tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();
203
tune_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
204
205
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_INITIALISED);
206
}
207
208
// load_orig_gains - set gains to their original values
209
// called by stop and failed functions
210
void AC_AutoTune_Multi::load_orig_gains()
211
{
212
attitude_control->bf_feedforward(orig_bf_feedforward);
213
if (roll_enabled()) {
214
if (!is_zero(orig_roll_rp)) {
215
attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);
216
attitude_control->get_rate_roll_pid().set_kI(orig_roll_ri);
217
attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);
218
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
219
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
220
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
221
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
222
attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);
223
attitude_control->set_accel_roll_max_cdss(orig_roll_accel);
224
}
225
}
226
if (pitch_enabled()) {
227
if (!is_zero(orig_pitch_rp)) {
228
attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);
229
attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_ri);
230
attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);
231
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
232
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
233
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
234
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
235
attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);
236
attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel);
237
}
238
}
239
if (yaw_enabled() || yaw_d_enabled()) {
240
if (!is_zero(orig_yaw_rp)) {
241
attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);
242
attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_ri);
243
attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);
244
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
245
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
246
attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);
247
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
248
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
249
attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);
250
attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel);
251
}
252
}
253
}
254
255
// load_tuned_gains - load tuned gains
256
void AC_AutoTune_Multi::load_tuned_gains()
257
{
258
if (!attitude_control->get_bf_feedforward()) {
259
attitude_control->bf_feedforward(true);
260
attitude_control->set_accel_roll_max_cdss(0.0);
261
attitude_control->set_accel_pitch_max_cdss(0.0);
262
}
263
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {
264
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
265
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
266
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
267
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
268
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
269
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
270
attitude_control->set_accel_roll_max_cdss(tune_roll_accel);
271
}
272
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {
273
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
274
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
275
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
276
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
277
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
278
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
279
attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel);
280
}
281
if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled())
282
|| ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) {
283
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
284
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
285
if (yaw_d_enabled()) {
286
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
287
}
288
if (yaw_enabled()) {
289
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
290
}
291
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
292
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
293
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
294
attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel);
295
}
296
}
297
298
// load_intra_test_gains - gains used between tests
299
// called during testing mode's update-gains step to set gains ahead of return-to-level step
300
void AC_AutoTune_Multi::load_intra_test_gains()
301
{
302
// we are restarting tuning so reset gains to tuning-start gains (i.e. low I term)
303
// sanity check the gains
304
attitude_control->bf_feedforward(true);
305
if (roll_enabled()) {
306
attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);
307
attitude_control->get_rate_roll_pid().set_kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
308
attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);
309
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
310
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
311
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
312
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
313
attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);
314
}
315
if (pitch_enabled()) {
316
attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);
317
attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
318
attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);
319
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
320
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
321
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
322
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
323
attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);
324
}
325
if (yaw_enabled() || yaw_d_enabled()) {
326
attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);
327
attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
328
attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);
329
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
330
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
331
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
332
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
333
attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);
334
attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);
335
}
336
}
337
338
// load_test_gains - load the to-be-tested gains for a single axis
339
// called by control_attitude() just before it beings testing a gain (i.e. just before it twitches)
340
void AC_AutoTune_Multi::load_test_gains()
341
{
342
switch (axis) {
343
case AxisType::ROLL:
344
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
345
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp * 0.01);
346
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
347
attitude_control->get_rate_roll_pid().set_ff(0.0);
348
attitude_control->get_rate_roll_pid().set_kDff(0.0);
349
attitude_control->get_rate_roll_pid().set_filt_T_hz(0.0);
350
attitude_control->get_rate_roll_pid().set_slew_limit(0.0);
351
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
352
break;
353
case AxisType::PITCH:
354
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
355
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp * 0.01);
356
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
357
attitude_control->get_rate_pitch_pid().set_ff(0.0);
358
attitude_control->get_rate_pitch_pid().set_kDff(0.0);
359
attitude_control->get_rate_pitch_pid().set_filt_T_hz(0.0);
360
attitude_control->get_rate_pitch_pid().set_slew_limit(0.0);
361
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
362
break;
363
case AxisType::YAW:
364
case AxisType::YAW_D:
365
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
366
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp * 0.01);
367
attitude_control->get_rate_yaw_pid().set_ff(0.0);
368
attitude_control->get_rate_yaw_pid().set_kDff(0.0);
369
if (axis == AxisType::YAW_D) {
370
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
371
} else {
372
attitude_control->get_rate_yaw_pid().set_kD(0.0);
373
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
374
}
375
attitude_control->get_rate_yaw_pid().set_filt_T_hz(0.0);
376
attitude_control->get_rate_yaw_pid().set_slew_limit(0.0);
377
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
378
break;
379
}
380
}
381
382
// save_tuning_gains - save the final tuned gains for each axis
383
// save discovered gains to eeprom if autotuner is enabled (i.e. switch is in the high position)
384
void AC_AutoTune_Multi::save_tuning_gains()
385
{
386
// see if we successfully completed tuning of at least one axis
387
if (axes_completed == 0) {
388
return;
389
}
390
391
if (!attitude_control->get_bf_feedforward()) {
392
attitude_control->bf_feedforward_save(true);
393
attitude_control->save_accel_roll_max_cdss(0.0);
394
attitude_control->save_accel_pitch_max_cdss(0.0);
395
}
396
397
// sanity check the rate P values
398
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {
399
// rate roll gains
400
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
401
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
402
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
403
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
404
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
405
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
406
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
407
attitude_control->get_rate_roll_pid().save_gains();
408
409
// stabilize roll
410
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
411
attitude_control->get_angle_roll_p().save_gains();
412
413
// acceleration roll
414
attitude_control->save_accel_roll_max_cdss(tune_roll_accel);
415
416
// resave pids to originals in case the autotune is run again
417
orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
418
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
419
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
420
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
421
orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();
422
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
423
orig_roll_accel = attitude_control->get_accel_roll_max_cdss();
424
}
425
426
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {
427
// rate pitch gains
428
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
429
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
430
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
431
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
432
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
433
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
434
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
435
attitude_control->get_rate_pitch_pid().save_gains();
436
437
// stabilize pitch
438
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
439
attitude_control->get_angle_pitch_p().save_gains();
440
441
// acceleration pitch
442
attitude_control->save_accel_pitch_max_cdss(tune_pitch_accel);
443
444
// resave pids to originals in case the autotune is run again
445
orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
446
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
447
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
448
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
449
orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();
450
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
451
orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
452
}
453
454
if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled())
455
|| ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) {
456
// rate yaw gains
457
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
458
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
459
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
460
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
461
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
462
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
463
if (yaw_d_enabled()) {
464
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
465
}
466
if (yaw_enabled()) {
467
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
468
}
469
attitude_control->get_rate_yaw_pid().save_gains();
470
471
// stabilize yaw
472
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
473
attitude_control->get_angle_yaw_p().save_gains();
474
475
// acceleration yaw
476
attitude_control->save_accel_yaw_max_cdss(tune_yaw_accel);
477
478
// resave pids to originals in case the autotune is run again
479
orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
480
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
481
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
482
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
483
orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();
484
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
485
orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
486
orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
487
}
488
489
// update GCS and log save gains event
490
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
491
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SAVEDGAINS);
492
493
reset();
494
}
495
496
// report final gains for a given axis to GCS
497
void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const
498
{
499
switch (test_axis) {
500
case AxisType::ROLL:
501
report_axis_gains("Roll", tune_roll_rp, tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL, tune_roll_rd, tune_roll_sp, tune_roll_accel);
502
break;
503
case AxisType::PITCH:
504
report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL, tune_pitch_rd, tune_pitch_sp, tune_pitch_accel);
505
break;
506
case AxisType::YAW:
507
report_axis_gains("Yaw(E)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, 0, tune_yaw_sp, tune_yaw_accel);
508
break;
509
case AxisType::YAW_D:
510
report_axis_gains("Yaw(D)", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_sp, tune_yaw_accel);
511
break;
512
}
513
}
514
515
// report gain formatting helper
516
void AC_AutoTune_Multi::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const
517
{
518
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string);
519
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.3f, I:%0.3f, D:%0.4f",axis_string,rate_P,rate_I,rate_D);
520
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.3f, Max Accel:%0.0f",axis_string,angle_P,max_accel);
521
}
522
523
// twitching_test_rate - twitching tests
524
// update min and max and test for end conditions
525
void AC_AutoTune_Multi::twitching_test_rate(float angle, float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max, float &meas_angle_min)
526
{
527
const uint32_t now = AP_HAL::millis();
528
529
// capture maximum rate
530
if (rate > meas_rate_max) {
531
// the measurement is continuing to increase without stopping
532
meas_rate_max = rate;
533
meas_rate_min = rate;
534
meas_angle_min = angle;
535
}
536
537
// capture minimum measurement after the measurement has peaked (aka "bounce back")
538
if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.25)) {
539
// the measurement is bouncing back
540
meas_rate_min = rate;
541
meas_angle_min = angle;
542
}
543
544
// calculate early stopping time based on the time it takes to get to 63.21%
545
if (meas_rate_max < rate_target_max * 0.6321) {
546
// the measurement not reached the 63.21% threshold yet
547
step_time_limit_ms = (now - step_start_time_ms) * 3;
548
step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
549
}
550
551
if (meas_rate_max > rate_target_max) {
552
// the measured rate has passed the maximum target rate
553
step = UPDATE_GAINS;
554
}
555
556
if (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) {
557
// the measurement has passed 50% of the maximum rate and bounce back is larger than the threshold
558
step = UPDATE_GAINS;
559
}
560
561
if (now - step_start_time_ms >= step_time_limit_ms) {
562
// we have passed the maximum stop time
563
step = UPDATE_GAINS;
564
}
565
}
566
567
// twitching_test_rate - twitching tests
568
// update min and max and test for end conditions
569
void AC_AutoTune_Multi::twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min, float angle_min)
570
{
571
if (angle >= angle_max) {
572
if (is_equal(rate, meas_rate_min) || (angle_min > 0.95 * angle_max)) {
573
// we have reached the angle limit before completing the measurement of maximum and minimum
574
// reduce the maximum target rate
575
if (step_scaler > 0.2f) {
576
step_scaler *= 0.9f;
577
} else {
578
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
579
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Twitch Size Determination Failed");
580
mode = FAILED;
581
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
582
}
583
// ignore result and start test again
584
step = ABORT;
585
} else {
586
step = UPDATE_GAINS;
587
}
588
}
589
}
590
591
// twitching_test_angle - twitching tests
592
// update min and max and test for end conditions
593
void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angle_target_max, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max)
594
{
595
const uint32_t now = AP_HAL::millis();
596
597
// capture maximum angle
598
if (angle > meas_angle_max) {
599
// the angle still increasing
600
meas_angle_max = angle;
601
meas_angle_min = angle;
602
}
603
604
// capture minimum angle after we have reached a reasonable maximum angle
605
if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.25)) {
606
// the measurement is bouncing back
607
meas_angle_min = angle;
608
}
609
610
// capture maximum rate
611
if (rate > meas_rate_max) {
612
// the measurement is still increasing
613
meas_rate_max = rate;
614
meas_rate_min = rate;
615
}
616
617
// capture minimum rate after we have reached maximum rate
618
if (rate < meas_rate_min) {
619
// the measurement is still decreasing
620
meas_rate_min = rate;
621
}
622
623
// calculate early stopping time based on the time it takes to get to 63.21%
624
if (meas_angle_max < angle_target_max * 0.6321) {
625
// the measurement not reached the 63.21% threshold yet
626
step_time_limit_ms = (now - step_start_time_ms) * 3;
627
step_time_limit_ms = MIN(step_time_limit_ms, AUTOTUNE_TESTING_STEP_TIMEOUT_MS);
628
}
629
630
if (meas_angle_max > angle_target_max) {
631
// the measurement has passed the maximum angle
632
step = UPDATE_GAINS;
633
}
634
635
if (meas_angle_max - meas_angle_min > meas_angle_max * aggressiveness) {
636
// the measurement has passed 50% of the maximum angle and bounce back is larger than the threshold
637
step = UPDATE_GAINS;
638
}
639
640
if (now - step_start_time_ms >= step_time_limit_ms) {
641
// we have passed the maximum stop time
642
step = UPDATE_GAINS;
643
}
644
}
645
646
// twitching_measure_acceleration - measure rate of change of measurement
647
void AC_AutoTune_Multi::twitching_measure_acceleration(float &accel_average, float rate, float &rate_max) const
648
{
649
if (rate_max < rate) {
650
rate_max = rate;
651
accel_average = (1000.0 * rate_max) / (AP_HAL::millis() - step_start_time_ms);
652
}
653
}
654
655
// update gains for the rate p up tune type
656
void AC_AutoTune_Multi::updating_rate_p_up_all(AxisType test_axis)
657
{
658
switch (test_axis) {
659
case AxisType::ROLL:
660
updating_rate_p_up_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
661
break;
662
case AxisType::PITCH:
663
updating_rate_p_up_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
664
break;
665
case AxisType::YAW:
666
updating_rate_p_up_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max, false);
667
break;
668
case AxisType::YAW_D:
669
updating_rate_p_up_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
670
break;
671
}
672
}
673
674
// update gains for the rate d up tune type
675
void AC_AutoTune_Multi::updating_rate_d_up_all(AxisType test_axis)
676
{
677
switch (test_axis) {
678
case AxisType::ROLL:
679
updating_rate_d_up(tune_roll_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
680
break;
681
case AxisType::PITCH:
682
updating_rate_d_up(tune_pitch_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
683
break;
684
case AxisType::YAW:
685
updating_rate_d_up(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RLPF_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
686
break;
687
case AxisType::YAW_D:
688
updating_rate_d_up(tune_yaw_rd, min_d, AUTOTUNE_RD_MAX, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
689
break;
690
}
691
}
692
693
// update gains for the rate d down tune type
694
void AC_AutoTune_Multi::updating_rate_d_down_all(AxisType test_axis)
695
{
696
switch (test_axis) {
697
case AxisType::ROLL:
698
updating_rate_d_down(tune_roll_rd, min_d, AUTOTUNE_RD_STEP, tune_roll_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
699
break;
700
case AxisType::PITCH:
701
updating_rate_d_down(tune_pitch_rd, min_d, AUTOTUNE_RD_STEP, tune_pitch_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
702
break;
703
case AxisType::YAW:
704
updating_rate_d_down(tune_yaw_rLPF, AUTOTUNE_RLPF_MIN, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
705
break;
706
case AxisType::YAW_D:
707
updating_rate_d_down(tune_yaw_rd, min_d, AUTOTUNE_RD_STEP, tune_yaw_rp, AUTOTUNE_RP_MIN, AUTOTUNE_RP_MAX, AUTOTUNE_RP_STEP, target_rate, test_rate_min, test_rate_max);
708
break;
709
}
710
}
711
712
// update gains for the angle p up tune type
713
void AC_AutoTune_Multi::updating_angle_p_up_all(AxisType test_axis)
714
{
715
switch (test_axis) {
716
case AxisType::ROLL:
717
updating_angle_p_up(tune_roll_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
718
break;
719
case AxisType::PITCH:
720
updating_angle_p_up(tune_pitch_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
721
break;
722
case AxisType::YAW:
723
case AxisType::YAW_D:
724
updating_angle_p_up(tune_yaw_sp, AUTOTUNE_SP_MAX, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
725
break;
726
}
727
}
728
729
// update gains for the angle p down tune type
730
void AC_AutoTune_Multi::updating_angle_p_down_all(AxisType test_axis)
731
{
732
switch (test_axis) {
733
case AxisType::ROLL:
734
updating_angle_p_down(tune_roll_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
735
break;
736
case AxisType::PITCH:
737
updating_angle_p_down(tune_pitch_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
738
break;
739
case AxisType::YAW:
740
case AxisType::YAW_D:
741
updating_angle_p_down(tune_yaw_sp, AUTOTUNE_SP_MIN, AUTOTUNE_SP_STEP, target_angle, test_angle_max, test_rate_min, test_rate_max);
742
break;
743
}
744
}
745
746
// set gains post tune for the tune type
747
void AC_AutoTune_Multi::set_gains_post_tune(AxisType test_axis)
748
{
749
switch (tune_type) {
750
case RD_UP:
751
break;
752
case RD_DOWN:
753
switch (test_axis) {
754
case AxisType::ROLL:
755
tune_roll_rd = MAX(min_d, tune_roll_rd * AUTOTUNE_RD_BACKOFF);
756
tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF);
757
break;
758
case AxisType::PITCH:
759
tune_pitch_rd = MAX(min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);
760
tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF);
761
break;
762
case AxisType::YAW:
763
tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF);
764
tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);
765
break;
766
case AxisType::YAW_D:
767
tune_yaw_rd = MAX(min_d, tune_yaw_rd * AUTOTUNE_RD_BACKOFF);
768
tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);
769
break;
770
}
771
break;
772
case RP_UP:
773
switch (test_axis) {
774
case AxisType::ROLL:
775
tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RP_BACKOFF);
776
break;
777
case AxisType::PITCH:
778
tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);
779
break;
780
case AxisType::YAW:
781
case AxisType::YAW_D:
782
tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);
783
break;
784
}
785
break;
786
case SP_DOWN:
787
break;
788
case SP_UP:
789
switch (test_axis) {
790
case AxisType::ROLL:
791
tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF);
792
tune_roll_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
793
break;
794
case AxisType::PITCH:
795
tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);
796
tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
797
break;
798
case AxisType::YAW:
799
case AxisType::YAW_D:
800
tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);
801
tune_yaw_accel = MAX(AUTOTUNE_Y_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_Y_BACKOFF);
802
break;
803
}
804
break;
805
case RFF_UP:
806
case MAX_GAINS:
807
case TUNE_CHECK:
808
// this should never happen
809
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
810
break;
811
case TUNE_COMPLETE:
812
break;
813
}
814
}
815
816
// updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back
817
// optimize D term while keeping the maximum just below the target by adjusting P
818
void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
819
{
820
if (meas_rate_max > rate_target) {
821
// if maximum measurement was higher than target
822
// reduce P gain (which should reduce maximum)
823
tune_p -= tune_p * tune_p_step_ratio;
824
if (tune_p < tune_p_min) {
825
// P gain is at minimum so start reducing D
826
tune_p = tune_p_min;
827
tune_d -= tune_d * tune_d_step_ratio;
828
if (tune_d <= tune_d_min) {
829
// We have reached minimum D gain so stop tuning
830
tune_d = tune_d_min;
831
counter = AUTOTUNE_SUCCESS_COUNT;
832
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
833
// This may be mean AGGR should be increased or MIN_D decreased
834
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");
835
}
836
}
837
} else if ((meas_rate_max < rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
838
// we have not achieved a high enough maximum to get a good measurement of bounce back.
839
// increase P gain (which should increase maximum)
840
tune_p += tune_p * tune_p_step_ratio;
841
if (tune_p >= tune_p_max) {
842
tune_p = tune_p_max;
843
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
844
}
845
} else {
846
// we have a good measurement of bounce back
847
if (meas_rate_max-meas_rate_min > meas_rate_max * aggressiveness) {
848
// ignore the next result unless it is the same as this one
849
ignore_next = true;
850
// bounce back is bigger than our threshold so increment the success counter
851
counter++;
852
} else {
853
if (ignore_next == false) {
854
// bounce back is smaller than our threshold so decrement the success counter
855
if (counter > 0) {
856
counter--;
857
}
858
// increase D gain (which should increase bounce back)
859
tune_d += tune_d*tune_d_step_ratio * 2.0;
860
// stop tuning if we hit maximum D
861
if (tune_d >= tune_d_max) {
862
tune_d = tune_d_max;
863
counter = AUTOTUNE_SUCCESS_COUNT;
864
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
865
}
866
} else {
867
ignore_next = false;
868
}
869
}
870
}
871
}
872
873
// updating_rate_d_down - decrease D and adjust P to optimize the D term for no bounce back
874
// optimize D term while keeping the maximum just below the target by adjusting P
875
void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
876
{
877
if (meas_rate_max > rate_target) {
878
// if maximum measurement was higher than target
879
// reduce P gain (which should reduce maximum)
880
tune_p -= tune_p*tune_p_step_ratio;
881
if (tune_p < tune_p_min) {
882
// P gain is at minimum so start reducing D gain
883
tune_p = tune_p_min;
884
tune_d -= tune_d*tune_d_step_ratio;
885
if (tune_d <= tune_d_min) {
886
// We have reached minimum D so stop tuning
887
tune_d = tune_d_min;
888
counter = AUTOTUNE_SUCCESS_COUNT;
889
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
890
// This may be mean AGGR should be increased or MIN_D decreased
891
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");
892
}
893
}
894
} else if ((meas_rate_max < rate_target*(1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
895
// we have not achieved a high enough maximum to get a good measurement of bounce back.
896
// increase P gain (which should increase maximum)
897
tune_p += tune_p * tune_p_step_ratio;
898
if (tune_p >= tune_p_max) {
899
tune_p = tune_p_max;
900
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
901
}
902
} else {
903
// we have a good measurement of bounce back
904
if (meas_rate_max - meas_rate_min < meas_rate_max * aggressiveness) {
905
if (ignore_next == false) {
906
// bounce back is less than our threshold so increment the success counter
907
counter++;
908
} else {
909
ignore_next = false;
910
}
911
} else {
912
// ignore the next result unless it is the same as this one
913
ignore_next = true;
914
// bounce back is larger than our threshold so decrement the success counter
915
if (counter > 0) {
916
counter--;
917
}
918
// decrease D gain (which should decrease bounce back)
919
tune_d -= tune_d * tune_d_step_ratio;
920
// stop tuning if we hit minimum D
921
if (tune_d <= tune_d_min) {
922
tune_d = tune_d_min;
923
counter = AUTOTUNE_SUCCESS_COUNT;
924
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
925
// This may be mean AGGR should be increased or MIN_D decreased
926
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Min Rate D limit reached");
927
}
928
}
929
}
930
}
931
932
// updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing
933
// P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold
934
void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max, bool fail_min_d)
935
{
936
if (meas_rate_max > rate_target * (1.0 + 0.5 * aggressiveness)) {
937
// ignore the next result unless it is the same as this one
938
ignore_next = true;
939
// if maximum measurement was greater than target so increment the success counter
940
counter++;
941
} else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target * (1.0 - AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max - meas_rate_min > meas_rate_max * aggressiveness) && (tune_d > tune_d_min)) {
942
// if bounce back was larger than the threshold so decrement the success counter
943
if (counter > 0) {
944
counter--;
945
}
946
// decrease D gain (which should decrease bounce back)
947
tune_d -= tune_d * tune_d_step_ratio;
948
// do not decrease the D term past the minimum
949
if (tune_d <= tune_d_min) {
950
tune_d = tune_d_min;
951
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
952
if (fail_min_d) {
953
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate D Gain Determination Failed");
954
mode = FAILED;
955
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
956
}
957
}
958
// decrease P gain to match D gain reduction
959
tune_p -= tune_p * tune_p_step_ratio;
960
// do not decrease the P term past the minimum
961
if (tune_p <= tune_p_min) {
962
tune_p = tune_p_min;
963
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Rate P Gain Determination Failed");
964
mode = FAILED;
965
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
966
}
967
} else {
968
if (ignore_next == false) {
969
// if maximum measurement was lower than target so decrement the success counter
970
if (counter > 0) {
971
counter--;
972
}
973
// increase P gain (which should increase the maximum)
974
tune_p += tune_p * tune_p_step_ratio;
975
// stop tuning if we hit maximum P
976
if (tune_p >= tune_p_max) {
977
tune_p = tune_p_max;
978
counter = AUTOTUNE_SUCCESS_COUNT;
979
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
980
}
981
} else {
982
ignore_next = false;
983
}
984
}
985
}
986
987
// updating_angle_p_down - decrease P until we don't reach the target before time out
988
// P is decreased to ensure we are not overshooting the target
989
void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
990
{
991
if (meas_angle_max < angle_target * (1 + 0.5 * aggressiveness)) {
992
if (ignore_next == false) {
993
// if maximum measurement was lower than target so increment the success counter
994
counter++;
995
} else {
996
ignore_next = false;
997
}
998
} else {
999
// ignore the next result unless it is the same as this one
1000
ignore_next = true;
1001
// if maximum measurement was higher than target so decrement the success counter
1002
if (counter > 0) {
1003
counter--;
1004
}
1005
// decrease P gain (which should decrease the maximum)
1006
tune_p -= tune_p*tune_p_step_ratio;
1007
// stop tuning if we hit maximum P
1008
if (tune_p <= tune_p_min) {
1009
tune_p = tune_p_min;
1010
counter = AUTOTUNE_SUCCESS_COUNT;
1011
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
1012
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Angle P Gain Determination Failed");
1013
mode = FAILED;
1014
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
1015
}
1016
}
1017
}
1018
1019
// updating_angle_p_up - increase P to ensure the target is reached
1020
// P is increased until we achieve our target within a reasonable time
1021
void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
1022
{
1023
if ((meas_angle_max > angle_target * (1 + 0.5 * aggressiveness)) ||
1024
((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max * aggressiveness))) {
1025
// ignore the next result unless it is the same as this one
1026
ignore_next = true;
1027
// if maximum measurement was greater than target so increment the success counter
1028
counter++;
1029
} else {
1030
if (ignore_next == false) {
1031
// if maximum measurement was lower than target so decrement the success counter
1032
if (counter > 0) {
1033
counter--;
1034
}
1035
// increase P gain (which should increase the maximum)
1036
tune_p += tune_p * tune_p_step_ratio;
1037
// stop tuning if we hit maximum P
1038
if (tune_p >= tune_p_max) {
1039
tune_p = tune_p_max;
1040
counter = AUTOTUNE_SUCCESS_COUNT;
1041
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
1042
}
1043
} else {
1044
ignore_next = false;
1045
}
1046
}
1047
}
1048
1049
#if HAL_LOGGING_ENABLED
1050
void AC_AutoTune_Multi::Log_AutoTune()
1051
{
1052
if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
1053
switch (axis) {
1054
case AxisType::ROLL:
1055
Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);
1056
break;
1057
case AxisType::PITCH:
1058
Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);
1059
break;
1060
case AxisType::YAW:
1061
Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);
1062
break;
1063
case AxisType::YAW_D:
1064
Log_Write_AutoTune(axis, tune_type, target_angle, test_angle_min, test_angle_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max);
1065
break;
1066
}
1067
} else {
1068
switch (axis) {
1069
case AxisType::ROLL:
1070
Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);
1071
break;
1072
case AxisType::PITCH:
1073
Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);
1074
break;
1075
case AxisType::YAW:
1076
Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, test_accel_max);
1077
break;
1078
case AxisType::YAW_D:
1079
Log_Write_AutoTune(axis, tune_type, target_rate, test_rate_min, test_rate_max, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max);
1080
break;
1081
}
1082
}
1083
1084
}
1085
1086
void AC_AutoTune_Multi::Log_AutoTuneDetails()
1087
{
1088
Log_Write_AutoTuneDetails(lean_angle, rotation_rate);
1089
}
1090
1091
// @LoggerMessage: ATUN
1092
// @Description: Copter/QuadPlane AutoTune
1093
// @Vehicles: Copter, Plane
1094
// @Field: TimeUS: Time since system startup
1095
// @Field: Axis: which axis is currently being tuned
1096
// @Field: TuneStep: step in autotune process
1097
// @Field: Targ: target angle or rate, depending on tuning step
1098
// @Field: Min: measured minimum target angle or rate
1099
// @Field: Max: measured maximum target angle or rate
1100
// @Field: RP: new rate gain P term
1101
// @Field: RD: new rate gain D term
1102
// @Field: SP: new angle P term
1103
// @Field: ddt: maximum measured twitching acceleration
1104
1105
// Write an Autotune data packet
1106
void AC_AutoTune_Multi::Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
1107
{
1108
AP::logger().Write(
1109
"ATUN",
1110
"TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt",
1111
"s--ddd---o",
1112
"F--000---0",
1113
"QBBfffffff",
1114
AP_HAL::micros64(),
1115
axis,
1116
tune_step,
1117
meas_target*0.01,
1118
meas_min*0.01,
1119
meas_max*0.01,
1120
new_gain_rp,
1121
new_gain_rd,
1122
new_gain_sp,
1123
new_ddt);
1124
}
1125
1126
// Write an Autotune data packet
1127
void AC_AutoTune_Multi::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
1128
{
1129
// @LoggerMessage: ATDE
1130
// @Description: AutoTune data packet
1131
// @Field: TimeUS: Time since system startup
1132
// @Field: Angle: current angle
1133
// @Field: Rate: current angular rate
1134
AP::logger().WriteStreaming(
1135
"ATDE",
1136
"TimeUS,Angle,Rate",
1137
"sdk",
1138
"F00",
1139
"Qff",
1140
AP_HAL::micros64(),
1141
angle_cd*0.01,
1142
rate_cds*0.01);
1143
}
1144
#endif // HAL_LOGGING_ENABLED
1145
1146
float AC_AutoTune_Multi::target_angle_max_rp_cd() const
1147
{
1148
return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_RP_SCALE;
1149
}
1150
1151
float AC_AutoTune_Multi::target_angle_max_y_cd() const
1152
{
1153
// Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size
1154
return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MAX_Y_SCALE;
1155
}
1156
1157
float AC_AutoTune_Multi::target_angle_min_rp_cd() const
1158
{
1159
return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_RP_SCALE;
1160
}
1161
1162
float AC_AutoTune_Multi::target_angle_min_y_cd() const
1163
{
1164
// Aircraft with small lean angle will generally benefit from proportional smaller yaw twitch size
1165
return attitude_control->lean_angle_max_cd() * AUTOTUNE_TARGET_ANGLE_MIN_Y_SCALE;
1166
}
1167
1168
float AC_AutoTune_Multi::angle_lim_max_rp_cd() const
1169
{
1170
return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_ABORT_RP_SCALE;
1171
}
1172
1173
float AC_AutoTune_Multi::angle_lim_neg_rpy_cd() const
1174
{
1175
return attitude_control->lean_angle_max_cd() * AUTOTUNE_ANGLE_NEG_RP_SCALE;
1176
}
1177
1178
void AC_AutoTune_Multi::twitch_test_init()
1179
{
1180
float target_max_rate;
1181
switch (axis) {
1182
case AxisType::ROLL:
1183
angle_abort = target_angle_max_rp_cd();
1184
target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
1185
target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_roll()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
1186
target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_roll()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd());
1187
rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_D_hz() * 2.0);
1188
break;
1189
1190
case AxisType::PITCH:
1191
angle_abort = target_angle_max_rp_cd();
1192
target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler * AUTOTUNE_TARGET_RATE_RLLPIT_CDS);
1193
target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_pitch()) * 100.0, AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, target_max_rate);
1194
target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_pitch()) * 100.0, target_angle_min_rp_cd(), target_angle_max_rp_cd());
1195
rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_D_hz() * 2.0);
1196
break;
1197
1198
case AxisType::YAW:
1199
case AxisType::YAW_D:
1200
angle_abort = target_angle_max_y_cd();
1201
target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);
1202
target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw() * 0.75) * 100.0, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate);
1203
target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw() * 0.75) * 100.0, target_angle_min_y_cd(), target_angle_max_y_cd());
1204
if (axis == AxisType::YAW_D) {
1205
rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_yaw_pid().filt_D_hz() * 2.0);
1206
} else {
1207
rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ);
1208
}
1209
break;
1210
}
1211
1212
if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
1213
// todo: consider if this should be done for other axis
1214
rotation_rate_filt.reset(start_rate);
1215
} else {
1216
rotation_rate_filt.reset(0.0);
1217
}
1218
twitch_first_iter = true;
1219
test_rate_max = 0.0;
1220
test_rate_min = 0.0;
1221
test_angle_max = 0.0;
1222
test_angle_min = 0.0;
1223
accel_measure_rate_max = 0.0;
1224
}
1225
1226
//run twitch test
1227
void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign)
1228
{
1229
// disable rate limits
1230
attitude_control->use_sqrt_controller(false);
1231
// hold current attitude
1232
1233
if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
1234
// step angle targets on first iteration
1235
if (twitch_first_iter) {
1236
twitch_first_iter = false;
1237
// Testing increasing stabilize P gain so will set lean angle target
1238
switch (test_axis) {
1239
case AxisType::ROLL:
1240
// request roll to 20deg
1241
attitude_control->input_angle_step_bf_roll_pitch_yaw(dir_sign * target_angle, 0.0, 0.0);
1242
break;
1243
case AxisType::PITCH:
1244
// request pitch to 20deg
1245
attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, dir_sign * target_angle, 0.0);
1246
break;
1247
case AxisType::YAW:
1248
case AxisType::YAW_D:
1249
// request yaw to 20deg
1250
attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0, 0.0, dir_sign * target_angle);
1251
break;
1252
}
1253
} else {
1254
attitude_control->input_rate_bf_roll_pitch_yaw(0.0, 0.0, 0.0);
1255
}
1256
} else {
1257
// Testing rate P and D gains so will set body-frame rate targets.
1258
// Rate controller will use existing body-frame rates and convert to motor outputs
1259
// for all axes except the one we override here.
1260
switch (test_axis) {
1261
case AxisType::ROLL:
1262
// override body-frame roll rate
1263
attitude_control->input_rate_step_bf_roll_pitch_yaw(dir_sign * target_rate + start_rate, 0.0f, 0.0f);
1264
break;
1265
case AxisType::PITCH:
1266
// override body-frame pitch rate
1267
attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, dir_sign * target_rate + start_rate, 0.0f);
1268
break;
1269
case AxisType::YAW:
1270
case AxisType::YAW_D:
1271
// override body-frame yaw rate
1272
attitude_control->input_rate_step_bf_roll_pitch_yaw(0.0f, 0.0f, dir_sign * target_rate + start_rate);
1273
break;
1274
}
1275
}
1276
1277
// capture this iteration's rotation rate and lean angle
1278
float gyro_reading = 0;
1279
switch (test_axis) {
1280
case AxisType::ROLL:
1281
gyro_reading = ahrs_view->get_gyro().x;
1282
lean_angle = dir_sign * (ahrs_view->roll_sensor - (int32_t)start_angle);
1283
break;
1284
case AxisType::PITCH:
1285
gyro_reading = ahrs_view->get_gyro().y;
1286
lean_angle = dir_sign * (ahrs_view->pitch_sensor - (int32_t)start_angle);
1287
break;
1288
case AxisType::YAW:
1289
case AxisType::YAW_D:
1290
gyro_reading = ahrs_view->get_gyro().z;
1291
lean_angle = dir_sign * wrap_180_cd(ahrs_view->yaw_sensor-(int32_t)start_angle);
1292
break;
1293
}
1294
1295
// Add filter to measurements
1296
float filter_value;
1297
switch (tune_type) {
1298
case SP_DOWN:
1299
case SP_UP:
1300
filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0);
1301
break;
1302
default:
1303
filter_value = dir_sign * (ToDeg(gyro_reading) * 100.0 - start_rate);
1304
break;
1305
}
1306
rotation_rate = rotation_rate_filt.apply(filter_value,
1307
AP::scheduler().get_loop_period_s());
1308
1309
switch (tune_type) {
1310
case RD_UP:
1311
case RD_DOWN:
1312
twitching_test_rate(lean_angle, rotation_rate, target_rate, test_rate_min, test_rate_max, test_angle_min);
1313
twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);
1314
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
1315
break;
1316
case RP_UP:
1317
twitching_test_rate(lean_angle, rotation_rate, target_rate * (1 + 0.5 * aggressiveness), test_rate_min, test_rate_max, test_angle_min);
1318
twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);
1319
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
1320
break;
1321
case SP_DOWN:
1322
case SP_UP:
1323
twitching_test_angle(lean_angle, rotation_rate, target_angle * (1 + 0.5 * aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);
1324
twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, accel_measure_rate_max);
1325
break;
1326
case RFF_UP:
1327
case MAX_GAINS:
1328
case TUNE_CHECK:
1329
// this should never happen
1330
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1331
break;
1332
default:
1333
break;
1334
}
1335
}
1336
1337
// get_testing_step_timeout_ms accessor
1338
uint32_t AC_AutoTune_Multi::get_testing_step_timeout_ms() const
1339
{
1340
return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
1341
}
1342
1343
1344
#endif // AC_AUTOTUNE_ENABLED
1345
1346