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_Heli.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
support for autotune of helicopters. Based on original autotune code from ArduCopter, written by Leonard Hall
17
Converted to a library by Andrew Tridgell, and rewritten to include helicopters by Bill Geyer
18
*/
19
20
#include "AC_AutoTune_config.h"
21
22
#if AC_AUTOTUNE_ENABLED
23
24
#include "AC_AutoTune_Heli.h"
25
26
#include <AP_Logger/AP_Logger.h>
27
#include <GCS_MAVLink/GCS.h>
28
29
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step
30
31
#define AUTOTUNE_RD_STEP 0.0005f // minimum increment when increasing/decreasing Rate D term
32
#define AUTOTUNE_RP_STEP 0.005f // minimum increment when increasing/decreasing Rate P term
33
#define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term
34
#define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
35
#define AUTOTUNE_PI_RATIO_FINAL 1.0f // I is set 1x P after testing
36
#define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f // I is set 1x P after testing
37
#define AUTOTUNE_RD_MAX 0.020f // maximum Rate D value
38
#define AUTOTUNE_RP_MIN 0.02f // minimum Rate P value
39
#define AUTOTUNE_RP_MAX 0.3f // maximum Rate P value
40
#define AUTOTUNE_SP_MAX 10.0f // maximum Stab P value
41
#define AUTOTUNE_SP_MIN 3.0f // maximum Stab P value
42
#define AUTOTUNE_RFF_MAX 0.5f // maximum Stab P value
43
#define AUTOTUNE_RFF_MIN 0.025f // maximum Stab P value
44
#define AUTOTUNE_RD_BACKOFF 1.0f // Rate D gains are reduced to 50% of their maximum value discovered during tuning
45
#define AUTOTUNE_RP_BACKOFF 1.0f // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning
46
#define AUTOTUNE_SP_BACKOFF 1.0f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
47
#define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f // back off from maximum acceleration
48
#define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f // back off from maximum acceleration
49
50
#define AUTOTUNE_HELI_TARGET_ANGLE_RLLPIT_CD 1500 // target roll/pitch angle during AUTOTUNE FeedForward rate test
51
#define AUTOTUNE_HELI_TARGET_RATE_RLLPIT_CDS 5000 // target roll/pitch rate during AUTOTUNE FeedForward rate test
52
#define AUTOTUNE_FFI_RATIO_FOR_TESTING 0.5f // I is set 2x smaller than VFF during testing
53
#define AUTOTUNE_FFI_RATIO_FINAL 0.5f // I is set 0.5x VFF after testing
54
#define AUTOTUNE_RP_ACCEL_MIN 20000.0f // Minimum acceleration for Roll and Pitch
55
#define AUTOTUNE_Y_ACCEL_MIN 10000.0f // Minimum acceleration for Yaw
56
57
#define AUTOTUNE_SEQ_BITMASK_VFF 1
58
#define AUTOTUNE_SEQ_BITMASK_RATE_D 2
59
#define AUTOTUNE_SEQ_BITMASK_ANGLE_P 4
60
#define AUTOTUNE_SEQ_BITMASK_MAX_GAIN 8
61
#define AUTOTUNE_SEQ_BITMASK_TUNE_CHECK 16
62
63
// angle limits preserved from previous behaviour as Multi changed:
64
#define AUTOTUNE_ANGLE_TARGET_MAX_RP_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step
65
#define AUTOTUNE_ANGLE_TARGET_MIN_RP_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step
66
#define AUTOTUNE_ANGLE_TARGET_MAX_Y_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step
67
#define AUTOTUNE_ANGLE_TARGET_MIN_Y_CD 500 // target angle during TESTING_RATE step that will cause us to move to next step
68
#define AUTOTUNE_ANGLE_MAX_RP_CD 3000 // maximum allowable angle in degrees during testing
69
#define AUTOTUNE_ANGLE_NEG_RPY_CD 1000 // maximum allowable angle in degrees during testing
70
71
const AP_Param::GroupInfo AC_AutoTune_Heli::var_info[] = {
72
73
// @Param: AXES
74
// @DisplayName: Autotune axis bitmask
75
// @Description: 1-byte bitmap of axes to autotune
76
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
77
// @User: Standard
78
AP_GROUPINFO("AXES", 1, AC_AutoTune_Heli, axis_bitmask, 1),
79
80
// @Param: SEQ
81
// @DisplayName: AutoTune Sequence Bitmask
82
// @Description: 2-byte bitmask to select what tuning should be performed. Max gain automatically performed if Rate D is selected. Values: 7:All,1:VFF Only,2:Rate D/Rate P Only(incl max gain),4:Angle P Only,8:Max Gain Only,16:Tune Check,3:VFF and Rate D/Rate P(incl max gain),5:VFF and Angle P,6:Rate D/Rate P(incl max gain) and angle P
83
// @Bitmask: 0:VFF,1:Rate D/Rate P(incl max gain),2:Angle P,3:Max Gain Only,4:Tune Check
84
// @User: Standard
85
AP_GROUPINFO("SEQ", 2, AC_AutoTune_Heli, seq_bitmask, 3),
86
87
// @Param: FRQ_MIN
88
// @DisplayName: AutoTune minimum sweep frequency
89
// @Description: Defines the start frequency for sweeps and dwells
90
// @Range: 10 30
91
// @User: Standard
92
AP_GROUPINFO("FRQ_MIN", 3, AC_AutoTune_Heli, min_sweep_freq, 10.0f),
93
94
// @Param: FRQ_MAX
95
// @DisplayName: AutoTune maximum sweep frequency
96
// @Description: Defines the end frequency for sweeps and dwells
97
// @Range: 50 120
98
// @User: Standard
99
AP_GROUPINFO("FRQ_MAX", 4, AC_AutoTune_Heli, max_sweep_freq, 70.0f),
100
101
// @Param: GN_MAX
102
// @DisplayName: AutoTune maximum response gain
103
// @Description: Defines the response gain (output/input) to tune
104
// @Range: 1 2.5
105
// @User: Standard
106
AP_GROUPINFO("GN_MAX", 5, AC_AutoTune_Heli, max_resp_gain, 1.0f),
107
108
// @Param: VELXY_P
109
// @DisplayName: AutoTune velocity xy P gain
110
// @Description: Velocity xy P gain used to hold position during Max Gain, Rate P, and Rate D frequency sweeps
111
// @Range: 0 1
112
// @User: Standard
113
AP_GROUPINFO("VELXY_P", 6, AC_AutoTune_Heli, vel_hold_gain, 0.1f),
114
115
// @Param: ACC_MAX
116
// @DisplayName: AutoTune maximum allowable angular acceleration
117
// @Description: maximum angular acceleration in deg/s/s allowed during autotune maneuvers
118
// @Range: 1 4000
119
// @User: Standard
120
AP_GROUPINFO("ACC_MAX", 7, AC_AutoTune_Heli, accel_max, 0.0f),
121
122
// @Param: RAT_MAX
123
// @DisplayName: Autotune maximum allowable angular rate
124
// @Description: maximum angular rate in deg/s allowed during autotune maneuvers
125
// @Range: 0 500
126
// @User: Standard
127
AP_GROUPINFO("RAT_MAX", 8, AC_AutoTune_Heli, rate_max, 0.0f),
128
129
AP_GROUPEND
130
};
131
132
// constructor
133
AC_AutoTune_Heli::AC_AutoTune_Heli()
134
{
135
tune_seq[0] = TUNE_COMPLETE;
136
AP_Param::setup_object_defaults(this, var_info);
137
}
138
139
// initialize tests for each tune type
140
void AC_AutoTune_Heli::test_init()
141
{
142
AC_AutoTune_FreqResp::ResponseType resp_type = AC_AutoTune_FreqResp::ResponseType::RATE;
143
FreqRespCalcType calc_type = RATE;
144
FreqRespInput freq_resp_input = TARGET;
145
float freq_resp_amplitude = 5.0f; // amplitude in deg
146
float filter_freq = 10.0f;
147
switch (tune_type) {
148
case RFF_UP:
149
if (!is_positive(next_test_freq)) {
150
start_freq = 0.25f * M_2PI;
151
} else {
152
start_freq = next_test_freq;
153
}
154
stop_freq = start_freq;
155
filter_freq = start_freq;
156
157
attitude_control->bf_feedforward(false);
158
159
// variables needed to initialize frequency response object and test method
160
resp_type = AC_AutoTune_FreqResp::ResponseType::RATE;
161
calc_type = RATE;
162
freq_resp_input = TARGET;
163
pre_calc_cycles = 1.0f;
164
num_dwell_cycles = 3;
165
break;
166
case MAX_GAINS:
167
// initialize start frequency for sweep
168
if (!is_positive(next_test_freq)) {
169
start_freq = min_sweep_freq;
170
stop_freq = max_sweep_freq;
171
sweep_complete = true;
172
} else {
173
start_freq = next_test_freq;
174
stop_freq = start_freq;
175
test_accel_max = 0.0f;
176
}
177
filter_freq = start_freq;
178
179
attitude_control->bf_feedforward(false);
180
181
// variables needed to initialize frequency response object and test method
182
resp_type = AC_AutoTune_FreqResp::ResponseType::RATE;
183
calc_type = RATE;
184
freq_resp_input = MOTOR;
185
pre_calc_cycles = 6.25f;
186
num_dwell_cycles = 6;
187
break;
188
case RP_UP:
189
case RD_UP:
190
// initialize start frequency
191
if (!is_positive(next_test_freq)) {
192
// continue using frequency where testing left off with RD_UP completed
193
if (curr_data.phase > 150.0f && curr_data.phase < 180.0f && tune_type == RP_UP) {
194
start_freq = curr_data.freq;
195
// start with freq found for sweep where phase was 180 deg
196
} else if (!is_zero(sweep_tgt.ph180.freq)) {
197
start_freq = sweep_tgt.ph180.freq;
198
// otherwise start at min freq to step up in dwell frequency until phase > 160 deg
199
} else {
200
start_freq = min_sweep_freq;
201
}
202
} else {
203
start_freq = next_test_freq;
204
}
205
stop_freq = start_freq;
206
filter_freq = start_freq;
207
208
attitude_control->bf_feedforward(false);
209
210
// variables needed to initialize frequency response object and test method
211
resp_type = AC_AutoTune_FreqResp::ResponseType::RATE;
212
calc_type = RATE;
213
freq_resp_input = TARGET;
214
pre_calc_cycles = 6.25f;
215
num_dwell_cycles = 6;
216
break;
217
case SP_UP:
218
// initialize start frequency for sweep
219
if (!is_positive(next_test_freq)) {
220
start_freq = min_sweep_freq;
221
stop_freq = max_sweep_freq;
222
sweep_complete = true;
223
} else {
224
start_freq = next_test_freq;
225
stop_freq = start_freq;
226
test_accel_max = 0.0f;
227
}
228
filter_freq = start_freq;
229
attitude_control->bf_feedforward(false);
230
231
// variables needed to initialize frequency response object and test method
232
resp_type = AC_AutoTune_FreqResp::ResponseType::ANGLE;
233
calc_type = DRB;
234
freq_resp_input = TARGET;
235
pre_calc_cycles = 6.25f;
236
num_dwell_cycles = 6;
237
break;
238
case TUNE_CHECK:
239
// initialize start frequency
240
start_freq = min_sweep_freq;
241
stop_freq = max_sweep_freq;
242
test_accel_max = 0.0f;
243
filter_freq = start_freq;
244
245
// variables needed to initialize frequency response object and test method
246
resp_type = AC_AutoTune_FreqResp::ResponseType::ANGLE;
247
calc_type = ANGLE;
248
freq_resp_input = TARGET;
249
break;
250
default:
251
break;
252
}
253
254
if (!is_equal(start_freq,stop_freq)) {
255
input_type = AC_AutoTune_FreqResp::InputType::SWEEP;
256
} else {
257
input_type = AC_AutoTune_FreqResp::InputType::DWELL;
258
}
259
260
261
// initialize dwell test method
262
dwell_test_init(start_freq, stop_freq, freq_resp_amplitude, filter_freq, freq_resp_input, calc_type, resp_type, input_type);
263
264
start_angles = Vector3f(roll_cd, pitch_cd, desired_yaw_cd); // heli specific
265
}
266
267
// run tests for each tune type
268
void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign)
269
{
270
// if tune complete or beyond frequency range or no max allowed gains then exit testing
271
if (tune_type == TUNE_COMPLETE ||
272
((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) ||
273
((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq))){
274
275
load_gains(GAIN_ORIGINAL);
276
277
attitude_control->use_sqrt_controller(true);
278
279
get_poshold_attitude(roll_cd, pitch_cd, desired_yaw_cd);
280
281
// hold level attitude
282
attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);
283
284
if ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) {
285
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed");
286
mode = FAILED;
287
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
288
update_gcs(AUTOTUNE_MESSAGE_FAILED);
289
} else if ((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq)){
290
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Exceeded frequency range");
291
mode = FAILED;
292
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
293
update_gcs(AUTOTUNE_MESSAGE_FAILED);
294
} else if (tune_type == TUNE_COMPLETE) {
295
counter = AUTOTUNE_SUCCESS_COUNT;
296
step = UPDATE_GAINS;
297
}
298
return;
299
}
300
301
dwell_test_run(curr_data);
302
303
}
304
305
// heli specific gcs announcements
306
void AC_AutoTune_Heli::do_gcs_announcements()
307
{
308
const uint32_t now = AP_HAL::millis();
309
if (now - announce_time < AUTOTUNE_ANNOUNCE_INTERVAL_MS) {
310
return;
311
}
312
313
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: %s %s", axis_string(), type_string());
314
send_step_string();
315
switch (tune_type) {
316
case RFF_UP:
317
case RD_UP:
318
case RP_UP:
319
case MAX_GAINS:
320
case SP_UP:
321
case TUNE_CHECK:
322
if (is_equal(start_freq,stop_freq)) {
323
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Dwell");
324
} else {
325
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Sweep");
326
if (settle_time == 0) {
327
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f phase=%f", (double)(curr_test.freq), (double)(curr_test.gain), (double)(curr_test.phase));
328
}
329
}
330
break;
331
default:
332
break;
333
}
334
335
announce_time = now;
336
}
337
338
// send post test updates to user
339
void AC_AutoTune_Heli::do_post_test_gcs_announcements() {
340
float tune_rp = 0.0f;
341
float tune_rd = 0.0f;
342
float tune_rff = 0.0f;
343
float tune_sp = 0.0f;
344
float tune_accel = 0.0f;
345
346
switch (axis) {
347
case AxisType::ROLL:
348
tune_rp = tune_roll_rp;
349
tune_rd = tune_roll_rd;
350
tune_rff = tune_roll_rff;
351
tune_sp = tune_roll_sp;
352
tune_accel = tune_roll_accel;
353
break;
354
case AxisType::PITCH:
355
tune_rp = tune_pitch_rp;
356
tune_rd = tune_pitch_rd;
357
tune_rff = tune_pitch_rff;
358
tune_sp = tune_pitch_sp;
359
tune_accel = tune_pitch_accel;
360
break;
361
case AxisType::YAW:
362
case AxisType::YAW_D:
363
tune_rp = tune_yaw_rp;
364
tune_rd = tune_yaw_rd;
365
tune_rff = tune_yaw_rff;
366
tune_sp = tune_yaw_sp;
367
tune_accel = tune_yaw_accel;
368
break;
369
}
370
371
if (step == UPDATE_GAINS) {
372
switch (tune_type) {
373
case RFF_UP:
374
case RP_UP:
375
case RD_UP:
376
case SP_UP:
377
case MAX_GAINS:
378
if (is_equal(start_freq,stop_freq)) {
379
// announce results of dwell
380
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(curr_data.freq), (double)(curr_data.gain));
381
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f", (double)(curr_data.phase));
382
if (tune_type == RP_UP) {
383
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: rate_p=%f", (double)(tune_rp));
384
} else if (tune_type == RD_UP) {
385
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: rate_d=%f", (double)(tune_rd));
386
} else if (tune_type == RFF_UP) {
387
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: rate_ff=%f", (double)(tune_rff));
388
} else if (tune_type == SP_UP) {
389
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: angle_p=%f tune_accel=%f max_accel=%f", (double)(tune_sp), (double)(tune_accel), (double)(test_accel_max));
390
}
391
} else {
392
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: max_freq=%f max_gain=%f", (double)(sweep_tgt.maxgain.freq), (double)(sweep_tgt.maxgain.gain));
393
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep_tgt.ph180.freq), (double)(sweep_tgt.ph180.gain));
394
}
395
break;
396
default:
397
break;
398
}
399
}
400
}
401
402
// backup_gains_and_initialise - store current gains as originals
403
// called before tuning starts to backup original gains
404
void AC_AutoTune_Heli::backup_gains_and_initialise()
405
{
406
AC_AutoTune::backup_gains_and_initialise();
407
408
// initializes dwell test sequence for rate_p_up and rate_d_up tests for tradheli
409
next_test_freq = 0.0f;
410
start_freq = 0.0f;
411
stop_freq = 0.0f;
412
413
orig_bf_feedforward = attitude_control->get_bf_feedforward();
414
415
// backup original pids and initialise tuned pid values
416
orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
417
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
418
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
419
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
420
orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz();
421
orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit();
422
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
423
orig_roll_accel = attitude_control->get_accel_roll_max_cdss();
424
orig_roll_rate = attitude_control->get_ang_vel_roll_max_degs();
425
tune_roll_rp = attitude_control->get_rate_roll_pid().kP();
426
tune_roll_rd = attitude_control->get_rate_roll_pid().kD();
427
tune_roll_rff = attitude_control->get_rate_roll_pid().ff();
428
tune_roll_sp = attitude_control->get_angle_roll_p().kP();
429
tune_roll_accel = attitude_control->get_accel_roll_max_cdss();
430
431
orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
432
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
433
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
434
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
435
orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz();
436
orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit();
437
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
438
orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
439
orig_pitch_rate = attitude_control->get_ang_vel_pitch_max_degs();
440
tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
441
tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
442
tune_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
443
tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();
444
tune_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
445
446
orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
447
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
448
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
449
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
450
orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz();
451
orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit();
452
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
453
orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
454
orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
455
orig_yaw_rate = attitude_control->get_ang_vel_yaw_max_degs();
456
tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
457
tune_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
458
tune_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
459
tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
460
tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();
461
tune_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
462
463
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_INITIALISED);
464
}
465
466
// load_orig_gains - set gains to their original values
467
// called by stop and failed functions
468
void AC_AutoTune_Heli::load_orig_gains()
469
{
470
attitude_control->bf_feedforward(orig_bf_feedforward);
471
if (roll_enabled()) {
472
load_gain_set(AxisType::ROLL, orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_sp, orig_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax, orig_roll_rate);
473
}
474
if (pitch_enabled()) {
475
load_gain_set(AxisType::PITCH, orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_sp, orig_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax, orig_pitch_rate);
476
}
477
if (yaw_enabled()) {
478
load_gain_set(AxisType::YAW, orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_sp, orig_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax, orig_yaw_rate);
479
}
480
}
481
482
// load_tuned_gains - load tuned gains
483
void AC_AutoTune_Heli::load_tuned_gains()
484
{
485
if (!attitude_control->get_bf_feedforward()) {
486
attitude_control->bf_feedforward(true);
487
attitude_control->set_accel_roll_max_cdss(0.0f);
488
attitude_control->set_accel_pitch_max_cdss(0.0f);
489
}
490
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled()) {
491
load_gain_set(AxisType::ROLL, tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax, orig_roll_rate);
492
}
493
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled()) {
494
load_gain_set(AxisType::PITCH, tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax, orig_pitch_rate);
495
}
496
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) {
497
load_gain_set(AxisType::YAW, tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, tune_yaw_rLPF, orig_yaw_smax, orig_yaw_rate);
498
}
499
}
500
501
// load_intra_test_gains - gains used between tests
502
// called during testing mode's update-gains step to set gains ahead of return-to-level step
503
void AC_AutoTune_Heli::load_intra_test_gains()
504
{
505
// we are restarting tuning so reset gains to tuning-start gains (i.e. low I term)
506
// sanity check the gains
507
attitude_control->bf_feedforward(true);
508
if (roll_enabled()) {
509
load_gain_set(AxisType::ROLL, orig_roll_rp, orig_roll_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING, orig_roll_rd, orig_roll_rff, orig_roll_sp, orig_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax, orig_roll_rate);
510
}
511
if (pitch_enabled()) {
512
load_gain_set(AxisType::PITCH, orig_pitch_rp, orig_pitch_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING, orig_pitch_rd, orig_pitch_rff, orig_pitch_sp, orig_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax, orig_pitch_rate);
513
}
514
if (yaw_enabled()) {
515
load_gain_set(AxisType::YAW, orig_yaw_rp, orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING, orig_yaw_rd, orig_yaw_rff, orig_yaw_sp, orig_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax, orig_yaw_rate);
516
}
517
}
518
519
// load_test_gains - load the to-be-tested gains for a single axis
520
// called by control_attitude() just before it beings testing a gain (i.e. just before it twitches)
521
void AC_AutoTune_Heli::load_test_gains()
522
{
523
float rate_p, rate_i, rate_d, rate_test_max, accel_test_max;
524
switch (axis) {
525
case AxisType::ROLL:
526
527
if (tune_type == TUNE_CHECK) {
528
rate_test_max = orig_roll_rate;
529
accel_test_max = tune_roll_accel;
530
} else {
531
// have attitude controller not perform rate limiting and angle P scaling based on accel max
532
rate_test_max = 0.0;
533
accel_test_max = 0.0;
534
}
535
if (tune_type == SP_UP || tune_type == TUNE_CHECK) {
536
rate_i = tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL;
537
} else {
538
// freeze integrator to hold trim by making i term small during rate controller tuning
539
rate_i = 0.01f * orig_roll_ri;
540
}
541
if (tune_type == MAX_GAINS && !is_zero(tune_roll_rff)) {
542
rate_p = 0.0f;
543
rate_d = 0.0f;
544
} else {
545
rate_p = tune_roll_rp;
546
rate_d = tune_roll_rd;
547
}
548
load_gain_set(AxisType::ROLL, rate_p, rate_i, rate_d, tune_roll_rff, tune_roll_sp, accel_test_max, orig_roll_fltt, 0.0f, 0.0f, rate_test_max);
549
break;
550
case AxisType::PITCH:
551
if (tune_type == TUNE_CHECK) {
552
rate_test_max = orig_pitch_rate;
553
accel_test_max = tune_pitch_accel;
554
} else {
555
// have attitude controller not perform rate limiting and angle P scaling based on accel max
556
rate_test_max = 0.0;
557
accel_test_max = 0.0;
558
}
559
if (tune_type == SP_UP || tune_type == TUNE_CHECK) {
560
rate_i = tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL;
561
} else {
562
// freeze integrator to hold trim by making i term small during rate controller tuning
563
rate_i = 0.01f * orig_pitch_ri;
564
}
565
if (tune_type == MAX_GAINS && !is_zero(tune_pitch_rff)) {
566
rate_p = 0.0f;
567
rate_d = 0.0f;
568
} else {
569
rate_p = tune_pitch_rp;
570
rate_d = tune_pitch_rd;
571
}
572
load_gain_set(AxisType::PITCH, rate_p, rate_i, rate_d, tune_pitch_rff, tune_pitch_sp, accel_test_max, orig_pitch_fltt, 0.0f, 0.0f, rate_test_max);
573
break;
574
case AxisType::YAW:
575
case AxisType::YAW_D:
576
if (tune_type == TUNE_CHECK) {
577
rate_test_max = orig_yaw_rate;
578
accel_test_max = tune_yaw_accel;
579
} else {
580
// have attitude controller not perform rate limiting and angle P scaling based on accel max
581
rate_test_max = 0.0;
582
accel_test_max = 0.0;
583
}
584
if (tune_type == SP_UP || tune_type == TUNE_CHECK) {
585
rate_i = tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL;
586
} else {
587
// freeze integrator to hold trim by making i term small during rate controller tuning
588
rate_i = 0.01f * orig_yaw_ri;
589
}
590
load_gain_set(AxisType::YAW, tune_yaw_rp, rate_i, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, accel_test_max, orig_yaw_fltt, tune_yaw_rLPF, 0.0f, rate_test_max);
591
break;
592
}
593
}
594
595
// load gains
596
void AC_AutoTune_Heli::load_gain_set(AxisType s_axis, float rate_p, float rate_i, float rate_d, float rate_ff, float angle_p, float max_accel, float rate_fltt, float rate_flte, float smax, float max_rate)
597
{
598
switch (s_axis) {
599
case AxisType::ROLL:
600
attitude_control->get_rate_roll_pid().set_kP(rate_p);
601
attitude_control->get_rate_roll_pid().set_kI(rate_i);
602
attitude_control->get_rate_roll_pid().set_kD(rate_d);
603
attitude_control->get_rate_roll_pid().set_ff(rate_ff);
604
attitude_control->get_rate_roll_pid().set_filt_T_hz(rate_fltt);
605
attitude_control->get_rate_roll_pid().set_slew_limit(smax);
606
attitude_control->get_angle_roll_p().set_kP(angle_p);
607
attitude_control->set_accel_roll_max_cdss(max_accel);
608
attitude_control->set_ang_vel_roll_max_degs(max_rate);
609
break;
610
case AxisType::PITCH:
611
attitude_control->get_rate_pitch_pid().set_kP(rate_p);
612
attitude_control->get_rate_pitch_pid().set_kI(rate_i);
613
attitude_control->get_rate_pitch_pid().set_kD(rate_d);
614
attitude_control->get_rate_pitch_pid().set_ff(rate_ff);
615
attitude_control->get_rate_pitch_pid().set_filt_T_hz(rate_fltt);
616
attitude_control->get_rate_pitch_pid().set_slew_limit(smax);
617
attitude_control->get_angle_pitch_p().set_kP(angle_p);
618
attitude_control->set_accel_pitch_max_cdss(max_accel);
619
attitude_control->set_ang_vel_pitch_max_degs(max_rate);
620
break;
621
case AxisType::YAW:
622
case AxisType::YAW_D:
623
attitude_control->get_rate_yaw_pid().set_kP(rate_p);
624
attitude_control->get_rate_yaw_pid().set_kI(rate_i);
625
attitude_control->get_rate_yaw_pid().set_kD(rate_d);
626
attitude_control->get_rate_yaw_pid().set_ff(rate_ff);
627
attitude_control->get_rate_yaw_pid().set_filt_T_hz(rate_fltt);
628
attitude_control->get_rate_yaw_pid().set_slew_limit(smax);
629
attitude_control->get_rate_yaw_pid().set_filt_E_hz(rate_flte);
630
attitude_control->get_angle_yaw_p().set_kP(angle_p);
631
attitude_control->set_accel_yaw_max_cdss(max_accel);
632
attitude_control->set_ang_vel_yaw_max_degs(max_rate);
633
break;
634
}
635
}
636
637
// save_tuning_gains - save the final tuned gains for each axis
638
// save discovered gains to eeprom if autotuner is enabled (i.e. switch is in the high position)
639
void AC_AutoTune_Heli::save_tuning_gains()
640
{
641
// see if we successfully completed tuning of at least one axis
642
if (axes_completed == 0) {
643
return;
644
}
645
646
if (!attitude_control->get_bf_feedforward()) {
647
attitude_control->bf_feedforward_save(true);
648
attitude_control->save_accel_roll_max_cdss(0.0f);
649
attitude_control->save_accel_pitch_max_cdss(0.0f);
650
}
651
652
// sanity check the rate P values
653
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled()) {
654
load_gain_set(AxisType::ROLL, tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax, orig_roll_rate);
655
// save rate roll gains
656
attitude_control->get_rate_roll_pid().save_gains();
657
658
// save stabilize roll
659
attitude_control->get_angle_roll_p().save_gains();
660
661
// resave pids to originals in case the autotune is run again
662
orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
663
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
664
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
665
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
666
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
667
orig_roll_accel = attitude_control->get_accel_roll_max_cdss();
668
}
669
670
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled()) {
671
load_gain_set(AxisType::PITCH, tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax, orig_pitch_rate);
672
// save rate pitch gains
673
attitude_control->get_rate_pitch_pid().save_gains();
674
675
// save stabilize pitch
676
attitude_control->get_angle_pitch_p().save_gains();
677
678
// resave pids to originals in case the autotune is run again
679
orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
680
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
681
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
682
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
683
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
684
orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
685
}
686
687
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) {
688
load_gain_set(AxisType::YAW, tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax, orig_yaw_rate);
689
// save rate yaw gains
690
attitude_control->get_rate_yaw_pid().save_gains();
691
692
// save stabilize yaw
693
attitude_control->get_angle_yaw_p().save_gains();
694
695
// resave pids to originals in case the autotune is run again
696
orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
697
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
698
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
699
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
700
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
701
orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
702
orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
703
}
704
705
// update GCS and log save gains event
706
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
707
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SAVEDGAINS);
708
709
reset();
710
}
711
712
// report final gains for a given axis to GCS
713
void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const
714
{
715
switch (test_axis) {
716
case AxisType::ROLL:
717
report_axis_gains("Roll", tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel);
718
break;
719
case AxisType::PITCH:
720
report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel);
721
break;
722
case AxisType::YAW:
723
case AxisType::YAW_D:
724
report_axis_gains("Yaw", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel);
725
break;
726
}
727
}
728
729
// report gain formatting helper
730
void AC_AutoTune_Heli::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const
731
{
732
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string);
733
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.4f, I:%0.4f, D:%0.5f, FF:%0.4f",axis_string,rate_P,rate_I,rate_D,rate_ff);
734
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.2f, Max Accel:%0.0f",axis_string,angle_P,max_accel);
735
}
736
737
void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float amplitude, float filt_freq, FreqRespInput freq_resp_input, FreqRespCalcType calc_type, AC_AutoTune_FreqResp::ResponseType resp_type, AC_AutoTune_FreqResp::InputType waveform_input_type)
738
{
739
test_input_type = waveform_input_type;
740
test_freq_resp_input = freq_resp_input;
741
test_calc_type = calc_type;
742
test_start_freq = start_frq;
743
//target attitude magnitude
744
tgt_attitude = radians(amplitude);
745
746
// initialize frequency response object
747
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
748
step_time_limit_ms = sweep_time_ms + 500;
749
reset_sweep_variables();
750
curr_test.gain = 0.0f;
751
curr_test.phase = 0.0f;
752
chirp_input.init(0.001f * sweep_time_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * sweep_time_ms, 0.0f);
753
} else {
754
if (!is_zero(start_frq)) {
755
// time limit set by adding the pre calc cycles with the dwell cycles. 500 ms added to account for settling with buffer.
756
step_time_limit_ms = (uint32_t) (2000 + ((float)num_dwell_cycles + pre_calc_cycles + 2.0f) * 1000.0f * M_2PI / start_frq);
757
}
758
chirp_input.init(0.001f * step_time_limit_ms, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * step_time_limit_ms, 0.0f);
759
}
760
761
freqresp_tgt.init(test_input_type, resp_type, num_dwell_cycles);
762
freqresp_mtr.init(test_input_type, resp_type, num_dwell_cycles);
763
764
dwell_start_time_ms = 0.0f;
765
settle_time = 200;
766
767
rotation_rate_filt.set_cutoff_frequency(filt_freq);
768
command_filt.set_cutoff_frequency(filt_freq);
769
target_rate_filt.set_cutoff_frequency(filt_freq);
770
771
rotation_rate_filt.reset(0);
772
command_filt.reset(0);
773
target_rate_filt.reset(0);
774
rotation_rate = 0.0f;
775
command_out = 0.0f;
776
filt_target_rate = 0.0f;
777
778
// filter at lower frequency to remove steady state
779
filt_command_reading.set_cutoff_frequency(0.2f * filt_freq);
780
filt_gyro_reading.set_cutoff_frequency(0.05f * filt_freq);
781
filt_tgt_rate_reading.set_cutoff_frequency(0.05f * filt_freq);
782
filt_att_fdbk_from_velxy_cd.set_cutoff_frequency(0.2f * filt_freq);
783
784
curr_test_mtr = {};
785
curr_test_tgt = {};
786
cycle_complete_tgt = false;
787
cycle_complete_mtr = false;
788
sweep_complete = false;
789
790
}
791
792
void AC_AutoTune_Heli::dwell_test_run(sweep_info &test_data)
793
{
794
float gyro_reading = 0.0f;
795
float command_reading = 0.0f;
796
float tgt_rate_reading = 0.0f;
797
const uint32_t now = AP_HAL::millis();
798
float target_angle_cd = 0.0f;
799
float dwell_freq = test_start_freq;
800
801
float cycle_time_ms = 0;
802
if (!is_zero(dwell_freq)) {
803
cycle_time_ms = 1000.0f * M_2PI / dwell_freq;
804
}
805
806
// body frame calculation of velocity
807
Vector3f velocity_ned, velocity_bf;
808
if (ahrs_view->get_velocity_NED(velocity_ned)) {
809
velocity_bf.x = velocity_ned.x * ahrs_view->cos_yaw() + velocity_ned.y * ahrs_view->sin_yaw();
810
velocity_bf.y = -velocity_ned.x * ahrs_view->sin_yaw() + velocity_ned.y * ahrs_view->cos_yaw();
811
}
812
813
if (settle_time == 0) {
814
dwell_freq = chirp_input.get_frequency_rads();
815
float tgt_att_limited = tgt_attitude;
816
if (is_positive(dwell_freq)) {
817
float tgt_att_temp = tgt_attitude;
818
if (is_positive(rate_max)) {
819
float ang_limit_rate = radians(rate_max) / dwell_freq;
820
tgt_att_temp = MIN(ang_limit_rate, tgt_attitude);
821
}
822
if (is_positive(accel_max)) {
823
float ang_limit_accel = radians(accel_max) / sq(dwell_freq);
824
tgt_att_limited = MIN(ang_limit_accel, tgt_att_temp);
825
} else {
826
tgt_att_limited = tgt_att_temp;
827
}
828
}
829
target_angle_cd = -chirp_input.update((now - dwell_start_time_ms) * 0.001, degrees(tgt_att_limited) * 100.0f);
830
dwell_freq = chirp_input.get_frequency_rads();
831
const Vector2f att_fdbk {
832
-5730.0f * vel_hold_gain * velocity_bf.y,
833
5730.0f * vel_hold_gain * velocity_bf.x
834
};
835
filt_att_fdbk_from_velxy_cd.apply(att_fdbk, AP::scheduler().get_loop_period_s());
836
} else {
837
target_angle_cd = 0.0f;
838
trim_yaw_tgt_reading_cd = (float)attitude_control->get_att_target_euler_cd().z;
839
trim_yaw_heading_reading_cd = (float)ahrs_view->yaw_sensor;
840
dwell_start_time_ms = now;
841
filt_att_fdbk_from_velxy_cd.reset(Vector2f(0.0f,0.0f));
842
settle_time--;
843
}
844
845
const Vector2f trim_angle_cd {
846
constrain_float(filt_att_fdbk_from_velxy_cd.get().x, -2000.0f, 2000.0f),
847
constrain_float(filt_att_fdbk_from_velxy_cd.get().y, -2000.0f, 2000.0f)
848
};
849
850
switch (axis) {
851
case AxisType::ROLL:
852
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_angle_cd + trim_angle_cd.x, trim_angle_cd.y, 0.0f);
853
command_reading = motors->get_roll();
854
if (test_calc_type == DRB) {
855
tgt_rate_reading = radians(target_angle_cd * 0.01f);
856
gyro_reading = radians(((float)ahrs_view->roll_sensor + trim_angle_cd.x - target_angle_cd) * 0.01f);
857
} else if (test_calc_type == RATE) {
858
tgt_rate_reading = attitude_control->rate_bf_targets().x;
859
gyro_reading = ahrs_view->get_gyro().x;
860
} else {
861
tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().x * 0.01f);
862
gyro_reading = radians((float)ahrs_view->roll_sensor * 0.01f);
863
}
864
break;
865
case AxisType::PITCH:
866
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(trim_angle_cd.x, target_angle_cd + trim_angle_cd.y, 0.0f);
867
command_reading = motors->get_pitch();
868
if (test_calc_type == DRB) {
869
tgt_rate_reading = radians(target_angle_cd * 0.01f);
870
gyro_reading = radians(((float)ahrs_view->pitch_sensor + trim_angle_cd.y - target_angle_cd) * 0.01f);
871
} else if (test_calc_type == RATE) {
872
tgt_rate_reading = attitude_control->rate_bf_targets().y;
873
gyro_reading = ahrs_view->get_gyro().y;
874
} else {
875
tgt_rate_reading = radians((float)attitude_control->get_att_target_euler_cd().y * 0.01f);
876
gyro_reading = radians((float)ahrs_view->pitch_sensor * 0.01f);
877
}
878
break;
879
case AxisType::YAW:
880
case AxisType::YAW_D:
881
attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading_cd + target_angle_cd), false);
882
command_reading = motors->get_yaw();
883
if (test_calc_type == DRB) {
884
tgt_rate_reading = radians(target_angle_cd * 0.01f);
885
gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd - target_angle_cd)) * 0.01f);
886
} else if (test_calc_type == RATE) {
887
tgt_rate_reading = attitude_control->rate_bf_targets().z;
888
gyro_reading = ahrs_view->get_gyro().z;
889
} else {
890
tgt_rate_reading = radians((wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading_cd)) * 0.01f);
891
gyro_reading = radians((wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading_cd)) * 0.01f);
892
}
893
break;
894
}
895
896
if (settle_time == 0) {
897
filt_command_reading.apply(command_reading, AP::scheduler().get_loop_period_s());
898
filt_gyro_reading.apply(gyro_reading, AP::scheduler().get_loop_period_s());
899
filt_tgt_rate_reading.apply(tgt_rate_reading, AP::scheduler().get_loop_period_s());
900
} else {
901
filt_command_reading.reset(command_reading);
902
filt_gyro_reading.reset(gyro_reading);
903
filt_tgt_rate_reading.reset(tgt_rate_reading);
904
}
905
906
// looks at gain and phase of input rate to output rate
907
rotation_rate = rotation_rate_filt.apply((gyro_reading - filt_gyro_reading.get()),
908
AP::scheduler().get_loop_period_s());
909
filt_target_rate = target_rate_filt.apply((tgt_rate_reading - filt_tgt_rate_reading.get()),
910
AP::scheduler().get_loop_period_s());
911
command_out = command_filt.apply((command_reading - filt_command_reading.get()),
912
AP::scheduler().get_loop_period_s());
913
914
float dwell_gain_mtr = 0.0f;
915
float dwell_phase_mtr = 0.0f;
916
float dwell_gain_tgt = 0.0f;
917
float dwell_phase_tgt = 0.0f;
918
// wait for dwell to start before determining gain and phase
919
if ((float)(now - dwell_start_time_ms) > pre_calc_cycles * cycle_time_ms || (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP && settle_time == 0)) {
920
freqresp_mtr.update(command_out,command_out,rotation_rate, dwell_freq);
921
freqresp_tgt.update(command_out,filt_target_rate,rotation_rate, dwell_freq);
922
923
if (freqresp_mtr.is_cycle_complete()) {
924
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
925
if (is_zero(curr_test_mtr.freq) && freqresp_mtr.get_freq() < test_start_freq) {
926
// don't set data since captured frequency is below the start frequency
927
} else {
928
curr_test_mtr.freq = freqresp_mtr.get_freq();
929
curr_test_mtr.gain = freqresp_mtr.get_gain();
930
curr_test_mtr.phase = freqresp_mtr.get_phase();
931
}
932
// reset cycle_complete to allow indication of next cycle
933
freqresp_mtr.reset_cycle_complete();
934
#if HAL_LOGGING_ENABLED
935
// log sweep data
936
Log_AutoTuneSweep();
937
#endif
938
} else {
939
dwell_gain_mtr = freqresp_mtr.get_gain();
940
dwell_phase_mtr = freqresp_mtr.get_phase();
941
cycle_complete_mtr = true;
942
}
943
}
944
945
if (freqresp_tgt.is_cycle_complete()) {
946
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
947
if (is_zero(curr_test_tgt.freq) && freqresp_tgt.get_freq() < test_start_freq) {
948
// don't set data since captured frequency is below the start frequency
949
} else {
950
curr_test_tgt.freq = freqresp_tgt.get_freq();
951
curr_test_tgt.gain = freqresp_tgt.get_gain();
952
curr_test_tgt.phase = freqresp_tgt.get_phase();
953
if (test_calc_type == DRB) {test_accel_max = freqresp_tgt.get_accel_max();}
954
}
955
// reset cycle_complete to allow indication of next cycle
956
freqresp_tgt.reset_cycle_complete();
957
#if HAL_LOGGING_ENABLED
958
// log sweep data
959
Log_AutoTuneSweep();
960
#endif
961
} else {
962
dwell_gain_tgt = freqresp_tgt.get_gain();
963
dwell_phase_tgt = freqresp_tgt.get_phase();
964
if (test_calc_type == DRB) {test_accel_max = freqresp_tgt.get_accel_max();}
965
cycle_complete_tgt = true;
966
}
967
}
968
969
if (test_freq_resp_input == TARGET) {
970
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
971
curr_test = curr_test_tgt;
972
} else {
973
test_data.freq = test_start_freq;
974
test_data.gain = dwell_gain_tgt;
975
test_data.phase = dwell_phase_tgt;
976
}
977
} else {
978
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
979
curr_test = curr_test_mtr;
980
} else {
981
test_data.freq = test_start_freq;
982
test_data.gain = dwell_gain_mtr;
983
test_data.phase = dwell_phase_mtr;
984
}
985
}
986
}
987
988
// set sweep data if a frequency sweep is being conducted
989
if (test_input_type == AC_AutoTune_FreqResp::InputType::SWEEP && (float)(now - dwell_start_time_ms) > 2.5f * cycle_time_ms) {
990
// track sweep phase to prevent capturing 180 deg and 270 deg data after phase has wrapped.
991
if (curr_test_tgt.phase > 180.0f && sweep_tgt.progress == 0) {
992
sweep_tgt.progress = 1;
993
} else if (curr_test_tgt.phase > 270.0f && sweep_tgt.progress == 1) {
994
sweep_tgt.progress = 2;
995
}
996
if (curr_test_tgt.phase <= 160.0f && curr_test_tgt.phase >= 150.0f && sweep_tgt.progress == 0) {
997
sweep_tgt.ph180 = curr_test_tgt;
998
}
999
if (curr_test_tgt.phase <= 250.0f && curr_test_tgt.phase >= 240.0f && sweep_tgt.progress == 1) {
1000
sweep_tgt.ph270 = curr_test_tgt;
1001
}
1002
if (curr_test_tgt.gain > sweep_tgt.maxgain.gain) {
1003
sweep_tgt.maxgain = curr_test_tgt;
1004
}
1005
// Determine sweep info for motor input to response output
1006
if (curr_test_mtr.phase > 180.0f && sweep_mtr.progress == 0) {
1007
sweep_mtr.progress = 1;
1008
} else if (curr_test_mtr.phase > 270.0f && sweep_mtr.progress == 1) {
1009
sweep_mtr.progress = 2;
1010
}
1011
if (curr_test_mtr.phase <= 160.0f && curr_test_mtr.phase >= 150.0f && sweep_mtr.progress == 0) {
1012
sweep_mtr.ph180 = curr_test_mtr;
1013
}
1014
if (curr_test_mtr.phase <= 250.0f && curr_test_mtr.phase >= 240.0f && sweep_mtr.progress == 1) {
1015
sweep_mtr.ph270 = curr_test_mtr;
1016
}
1017
if (curr_test_mtr.gain > sweep_mtr.maxgain.gain) {
1018
sweep_mtr.maxgain = curr_test_mtr;
1019
}
1020
1021
if (now - step_start_time_ms >= sweep_time_ms + 200) {
1022
// we have passed the maximum stop time
1023
sweep_complete = true;
1024
step = UPDATE_GAINS;
1025
}
1026
} else {
1027
if (now - step_start_time_ms >= step_time_limit_ms || (freqresp_tgt.is_cycle_complete() && freqresp_mtr.is_cycle_complete())) {
1028
if (now - step_start_time_ms >= step_time_limit_ms) {
1029
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Step time limit exceeded");
1030
}
1031
cycle_complete_tgt = false;
1032
cycle_complete_tgt = false;
1033
// we have passed the maximum stop time
1034
step = UPDATE_GAINS;
1035
}
1036
}
1037
}
1038
1039
// update gains for the rate p up tune type
1040
void AC_AutoTune_Heli::updating_rate_p_up_all(AxisType test_axis)
1041
{
1042
switch (test_axis) {
1043
case AxisType::ROLL:
1044
updating_rate_p_up(tune_roll_rp, curr_data, next_test_freq, max_rate_p);
1045
break;
1046
case AxisType::PITCH:
1047
updating_rate_p_up(tune_pitch_rp, curr_data, next_test_freq, max_rate_p);
1048
break;
1049
case AxisType::YAW:
1050
case AxisType::YAW_D:
1051
updating_rate_p_up(tune_yaw_rp, curr_data, next_test_freq, max_rate_p);
1052
break;
1053
}
1054
}
1055
1056
// update gains for the rate d up tune type
1057
void AC_AutoTune_Heli::updating_rate_d_up_all(AxisType test_axis)
1058
{
1059
switch (test_axis) {
1060
case AxisType::ROLL:
1061
updating_rate_d_up(tune_roll_rd, curr_data, next_test_freq, max_rate_d);
1062
break;
1063
case AxisType::PITCH:
1064
updating_rate_d_up(tune_pitch_rd, curr_data, next_test_freq, max_rate_d);
1065
break;
1066
case AxisType::YAW:
1067
case AxisType::YAW_D:
1068
updating_rate_d_up(tune_yaw_rd, curr_data, next_test_freq, max_rate_d);
1069
break;
1070
}
1071
}
1072
1073
// update gains for the rate ff up tune type
1074
void AC_AutoTune_Heli::updating_rate_ff_up_all(AxisType test_axis)
1075
{
1076
switch (test_axis) {
1077
case AxisType::ROLL:
1078
updating_rate_ff_up(tune_roll_rff, curr_data, next_test_freq);
1079
break;
1080
case AxisType::PITCH:
1081
updating_rate_ff_up(tune_pitch_rff, curr_data, next_test_freq);
1082
break;
1083
case AxisType::YAW:
1084
case AxisType::YAW_D:
1085
updating_rate_ff_up(tune_yaw_rff, curr_data, next_test_freq);
1086
// TODO make FF updating routine determine when to set rff gain to zero based on A/C response
1087
if (tune_yaw_rff <= AUTOTUNE_RFF_MIN && counter == AUTOTUNE_SUCCESS_COUNT) {
1088
tune_yaw_rff = 0.0f;
1089
}
1090
break;
1091
}
1092
}
1093
1094
// update gains for the angle p up tune type
1095
void AC_AutoTune_Heli::updating_angle_p_up_all(AxisType test_axis)
1096
{
1097
attitude_control->bf_feedforward(orig_bf_feedforward);
1098
1099
// sweep doesn't require gain update so return immediately after setting next test freq
1100
// determine next_test_freq for dwell testing
1101
if (sweep_complete && input_type == AC_AutoTune_FreqResp::InputType::SWEEP){
1102
// if a max gain frequency was found then set the start of the dwells to that freq otherwise start at min frequency
1103
if (!is_zero(sweep_tgt.maxgain.freq)) {
1104
next_test_freq = constrain_float(sweep_tgt.maxgain.freq, min_sweep_freq, max_sweep_freq);
1105
freq_max = next_test_freq;
1106
sp_prev_gain = sweep_tgt.maxgain.gain;
1107
phase_max = sweep_tgt.maxgain.phase;
1108
found_max_gain_freq = true;
1109
} else {
1110
next_test_freq = min_sweep_freq;
1111
}
1112
return;
1113
}
1114
1115
switch (test_axis) {
1116
case AxisType::ROLL:
1117
updating_angle_p_up(tune_roll_sp, curr_data, next_test_freq);
1118
break;
1119
case AxisType::PITCH:
1120
updating_angle_p_up(tune_pitch_sp, curr_data, next_test_freq);
1121
break;
1122
case AxisType::YAW:
1123
case AxisType::YAW_D:
1124
updating_angle_p_up(tune_yaw_sp, curr_data, next_test_freq);
1125
break;
1126
}
1127
}
1128
1129
// update gains for the max gain tune type
1130
void AC_AutoTune_Heli::updating_max_gains_all(AxisType test_axis)
1131
{
1132
// sweep doesn't require gain update so return immediately after setting next test freq
1133
// determine next_test_freq for dwell testing
1134
if (sweep_complete && input_type == AC_AutoTune_FreqResp::InputType::SWEEP) {
1135
// if a max gain frequency was found then set the start of the dwells to that freq otherwise start at min frequency
1136
if (!is_zero(sweep_mtr.ph180.freq)) {
1137
next_test_freq = constrain_float(sweep_mtr.ph180.freq, min_sweep_freq, max_sweep_freq);
1138
reset_maxgains_update_gain_variables();
1139
} else {
1140
next_test_freq = min_sweep_freq;
1141
}
1142
return;
1143
}
1144
1145
switch (test_axis) {
1146
case AxisType::ROLL:
1147
updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_roll_rp, tune_roll_rd);
1148
break;
1149
case AxisType::PITCH:
1150
updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_pitch_rp, tune_pitch_rd);
1151
break;
1152
case AxisType::YAW:
1153
case AxisType::YAW_D:
1154
updating_max_gains(curr_data, next_test_freq, max_rate_p, max_rate_d, tune_yaw_rp, tune_yaw_rd);
1155
// rate P and rate D can be non zero for yaw and need to be included in the max allowed gain
1156
if (!is_zero(max_rate_p.max_allowed) && counter == AUTOTUNE_SUCCESS_COUNT) {
1157
max_rate_p.max_allowed += tune_yaw_rp;
1158
}
1159
if (!is_zero(max_rate_d.max_allowed) && counter == AUTOTUNE_SUCCESS_COUNT) {
1160
max_rate_d.max_allowed += tune_yaw_rd;
1161
}
1162
break;
1163
}
1164
}
1165
1166
// set gains post tune for the tune type
1167
void AC_AutoTune_Heli::set_gains_post_tune(AxisType test_axis)
1168
{
1169
switch (tune_type) {
1170
case RD_UP:
1171
switch (test_axis) {
1172
case AxisType::ROLL:
1173
tune_roll_rd = MAX(0.0f, tune_roll_rd * AUTOTUNE_RD_BACKOFF);
1174
break;
1175
case AxisType::PITCH:
1176
tune_pitch_rd = MAX(0.0f, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);
1177
break;
1178
case AxisType::YAW:
1179
case AxisType::YAW_D:
1180
tune_yaw_rd = MAX(0.0f, tune_yaw_rd * AUTOTUNE_RD_BACKOFF);
1181
break;
1182
}
1183
break;
1184
case RP_UP:
1185
switch (test_axis) {
1186
case AxisType::ROLL:
1187
tune_roll_rp = MAX(0.0f, tune_roll_rp * AUTOTUNE_RP_BACKOFF);
1188
break;
1189
case AxisType::PITCH:
1190
tune_pitch_rp = MAX(0.0f, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);
1191
break;
1192
case AxisType::YAW:
1193
case AxisType::YAW_D:
1194
tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);
1195
break;
1196
}
1197
break;
1198
case SP_UP:
1199
switch (test_axis) {
1200
case AxisType::ROLL:
1201
tune_roll_sp = MAX(AUTOTUNE_SP_MIN, tune_roll_sp * AUTOTUNE_SP_BACKOFF);
1202
break;
1203
case AxisType::PITCH:
1204
tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);
1205
break;
1206
case AxisType::YAW:
1207
case AxisType::YAW_D:
1208
tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);
1209
break;
1210
}
1211
break;
1212
case RFF_UP:
1213
break;
1214
default:
1215
break;
1216
}
1217
}
1218
1219
// updating_rate_ff_up - adjust FF to ensure the target is reached
1220
// FF is adjusted until rate requested is achieved
1221
void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, sweep_info &test_data, float &next_freq)
1222
{
1223
float tune_tgt = 0.95;
1224
float tune_tol = 0.025;
1225
next_freq = test_data.freq;
1226
1227
// handle axes where FF gain is initially zero
1228
if (test_data.gain < tune_tgt - tune_tol && !is_positive(tune_ff)) {
1229
tune_ff = 0.03f;
1230
return;
1231
}
1232
1233
if (test_data.gain < tune_tgt - 0.2 || test_data.gain > tune_tgt + 0.2) {
1234
tune_ff = tune_ff * constrain_float(tune_tgt / test_data.gain, 0.75, 1.25); //keep changes less than 25%
1235
} else if (test_data.gain < tune_tgt - 0.1 || test_data.gain > tune_tgt + 0.1) {
1236
if (test_data.gain < tune_tgt - 0.1) {
1237
tune_ff *= 1.05;
1238
} else {
1239
tune_ff *= 0.95;
1240
}
1241
} else if (test_data.gain < tune_tgt - tune_tol || test_data.gain > tune_tgt + tune_tol) {
1242
if (test_data.gain < tune_tgt - tune_tol) {
1243
tune_ff *= 1.02;
1244
} else {
1245
tune_ff *= 0.98;
1246
}
1247
} else if (test_data.gain >= tune_tgt - tune_tol && test_data.gain <= tune_tgt + tune_tol) {
1248
counter = AUTOTUNE_SUCCESS_COUNT;
1249
// reset next_freq for next test
1250
next_freq = 0.0f;
1251
tune_ff = constrain_float(tune_ff,0.0f,1.0f);
1252
}
1253
}
1254
1255
// updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not
1256
// exceed max response gain. A phase of 161 deg is used to conduct the tuning as this phase is where analytically
1257
// max gain to 6db gain margin is determined for a unity feedback controller.
1258
void AC_AutoTune_Heli::updating_rate_p_up(float &tune_p, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p)
1259
{
1260
float test_freq_incr = 0.25f * M_2PI;
1261
next_freq = test_data.freq;
1262
1263
sweep_info data_at_ph161;
1264
float sugg_freq;
1265
if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_ph161, sugg_freq)) {
1266
if (data_at_ph161.gain < max_resp_gain && tune_p < 0.6f * max_gain_p.max_allowed) {
1267
tune_p += 0.05f * max_gain_p.max_allowed;
1268
next_freq = data_at_ph161.freq;
1269
} else {
1270
counter = AUTOTUNE_SUCCESS_COUNT;
1271
// reset next_freq for next test
1272
next_freq = 0.0f;
1273
tune_p -= 0.05f * max_gain_p.max_allowed;
1274
tune_p = constrain_float(tune_p,0.0f,0.6f * max_gain_p.max_allowed);
1275
}
1276
} else {
1277
next_freq = sugg_freq;
1278
}
1279
}
1280
1281
// updating_rate_d_up - uses maximum allowable gain determined from max_gain test to determine rate d gain where the response
1282
// gain is at a minimum. A phase of 161 deg is used to conduct the tuning as this phase is where analytically
1283
// max gain to 6db gain margin is determined for a unity feedback controller.
1284
void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, sweep_info &test_data, float &next_freq, max_gain_data &max_gain_d)
1285
{
1286
float test_freq_incr = 0.25f * M_2PI; // set for 1/4 hz increments
1287
next_freq = test_data.freq;
1288
1289
sweep_info data_at_ph161;
1290
float sugg_freq;
1291
if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_ph161, sugg_freq)) {
1292
if ((data_at_ph161.gain < rd_prev_gain || is_zero(rd_prev_gain)) && tune_d < 0.6f * max_gain_d.max_allowed) {
1293
tune_d += 0.05f * max_gain_d.max_allowed;
1294
rd_prev_gain = data_at_ph161.gain;
1295
next_freq = data_at_ph161.freq;
1296
} else {
1297
counter = AUTOTUNE_SUCCESS_COUNT;
1298
// reset next freq and rd_prev_gain for next test
1299
next_freq = 0;
1300
rd_prev_gain = 0.0f;
1301
tune_d -= 0.05f * max_gain_d.max_allowed;
1302
tune_d = constrain_float(tune_d,0.0f,0.6f * max_gain_d.max_allowed);
1303
}
1304
} else {
1305
next_freq = sugg_freq;
1306
}
1307
}
1308
1309
// updating_angle_p_up - determines maximum angle p gain for pitch and roll. This is accomplished by determining the frequency
1310
// for the maximum response gain that is the disturbance rejection peak.
1311
void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, sweep_info &test_data, float &next_freq)
1312
{
1313
float test_freq_incr = 0.5f * M_2PI;
1314
float gain_incr = 0.5f;
1315
1316
if (is_zero(test_data.phase)) {
1317
// bad test point. increase slightly in hope of getting better result
1318
next_freq += 0.5f * test_freq_incr;
1319
return;
1320
}
1321
1322
if (!found_max_gain_freq) {
1323
if (test_data.gain > max_resp_gain && tune_p > AUTOTUNE_SP_MIN) {
1324
// exceeded max response gain already, reduce tuning gain to remain under max response gain
1325
tune_p -= gain_incr;
1326
// force counter to stay on frequency
1327
next_freq = test_data.freq;
1328
return;
1329
} else if (test_data.gain > max_resp_gain && tune_p <= AUTOTUNE_SP_MIN) {
1330
// exceeded max response gain at the minimum allowable tuning gain. terminate testing.
1331
tune_p = AUTOTUNE_SP_MIN;
1332
counter = AUTOTUNE_SUCCESS_COUNT;
1333
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
1334
} else if (test_data.gain > sp_prev_gain) {
1335
freq_max = test_data.freq;
1336
phase_max = test_data.phase;
1337
sp_prev_gain = test_data.gain;
1338
next_freq = test_data.freq + test_freq_incr;
1339
return;
1340
// Gain is expected to continue decreasing past gain peak. declare max gain freq found and refine search.
1341
} else if (test_data.gain < 0.95f * sp_prev_gain) {
1342
found_max_gain_freq = true;
1343
next_freq = freq_max + 0.5 * test_freq_incr;
1344
return;
1345
} else {
1346
next_freq = test_data.freq + test_freq_incr;
1347
return;
1348
}
1349
}
1350
1351
// refine peak
1352
if (!found_peak) {
1353
// look at frequency above max gain freq found
1354
if (test_data.freq > freq_max && test_data.gain > sp_prev_gain) {
1355
// found max at frequency greater than initial max gain frequency
1356
found_peak = true;
1357
} else if (test_data.freq > freq_max && test_data.gain < sp_prev_gain) {
1358
// look at frequency below initial max gain frequency
1359
next_freq = test_data.freq - 0.5 * test_freq_incr;
1360
return;
1361
} else if (test_data.freq < freq_max && test_data.gain > sp_prev_gain) {
1362
// found max at frequency less than initial max gain frequency
1363
found_peak = true;
1364
} else {
1365
found_peak = true;
1366
test_data.freq = freq_max;
1367
test_data.gain = sp_prev_gain;
1368
}
1369
sp_prev_gain = test_data.gain;
1370
}
1371
1372
// start increasing gain
1373
if (found_max_gain_freq && found_peak) {
1374
if (test_data.gain < max_resp_gain && tune_p < AUTOTUNE_SP_MAX) {
1375
tune_p += gain_incr;
1376
next_freq = test_data.freq;
1377
if (tune_p >= AUTOTUNE_SP_MAX) {
1378
tune_p = AUTOTUNE_SP_MAX;
1379
counter = AUTOTUNE_SUCCESS_COUNT;
1380
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
1381
}
1382
sp_prev_gain = test_data.gain;
1383
} else if (test_data.gain > 1.1f * max_resp_gain && tune_p > AUTOTUNE_SP_MIN) {
1384
tune_p -= gain_incr;
1385
} else {
1386
// adjust tuning gain so max response gain is not exceeded
1387
if (sp_prev_gain < max_resp_gain && test_data.gain > max_resp_gain) {
1388
float adj_factor = (max_resp_gain - test_data.gain) / (test_data.gain - sp_prev_gain);
1389
tune_p = tune_p + gain_incr * adj_factor;
1390
}
1391
counter = AUTOTUNE_SUCCESS_COUNT;
1392
}
1393
}
1394
if (counter == AUTOTUNE_SUCCESS_COUNT) {
1395
next_freq = 0.0f; //initializes next test that uses dwell test
1396
sweep_complete = false;
1397
reset_sweep_variables();
1398
}
1399
}
1400
1401
// updating_max_gains: use dwells at increasing frequency to determine gain at which instability will occur. This uses the frequency
1402
// response of motor class input to rate response to determine the max allowable gain for rate P gain. A phase of 161 deg is used to
1403
// determine analytically the max gain to 6db gain margin for a unity feedback controller. Since acceleration can be more noisy, the
1404
// response of the motor class input to rate response to determine the max allowable gain for rate D gain. A phase of 251 deg is used
1405
// to determine analytically the max gain to 6db gain margin for a unity feedback controller.
1406
void AC_AutoTune_Heli::updating_max_gains(sweep_info &test_data, float &next_freq, max_gain_data &max_gain_p, max_gain_data &max_gain_d, float &tune_p, float &tune_d)
1407
{
1408
float test_freq_incr = 0.5f * M_2PI;
1409
next_freq = test_data.freq;
1410
1411
sweep_info data_at_phase;
1412
float sugg_freq;
1413
if (!found_max_p) {
1414
if (freq_search_for_phase(test_data, 161.0f, test_freq_incr, data_at_phase, sugg_freq)) {
1415
max_gain_p.freq = data_at_phase.freq;
1416
max_gain_p.gain = data_at_phase.gain;
1417
max_gain_p.phase = data_at_phase.phase;
1418
max_gain_p.max_allowed = powf(10.0f,-1 * (log10f(max_gain_p.gain) * 20.0f + 2.42) / 20.0f);
1419
// limit max gain allowed to be no more than 2x the max p gain limit to keep initial gains bounded
1420
max_gain_p.max_allowed = constrain_float(max_gain_p.max_allowed, 0.0f, 2.0f * AUTOTUNE_RP_MAX);
1421
found_max_p = true;
1422
if (!is_zero(sweep_mtr.ph270.freq)) {
1423
next_freq = sweep_mtr.ph270.freq;
1424
} else {
1425
next_freq = data_at_phase.freq;
1426
}
1427
} else {
1428
next_freq = sugg_freq;
1429
}
1430
} else if (!found_max_d) {
1431
if (freq_search_for_phase(test_data, 251.0f, test_freq_incr, data_at_phase, sugg_freq)) {
1432
max_gain_d.freq = data_at_phase.freq;
1433
max_gain_d.gain = data_at_phase.gain;
1434
max_gain_d.phase = data_at_phase.phase;
1435
max_gain_d.max_allowed = powf(10.0f,-1 * (log10f(max_gain_d.freq * max_gain_d.gain) * 20.0f + 2.42) / 20.0f);
1436
// limit max gain allowed to be no more than 2x the max d gain limit to keep initial gains bounded
1437
max_gain_d.max_allowed = constrain_float(max_gain_d.max_allowed, 0.0f, 2.0f * AUTOTUNE_RD_MAX);
1438
found_max_d = true;
1439
} else {
1440
next_freq = sugg_freq;
1441
}
1442
}
1443
1444
if (found_max_p && found_max_d) {
1445
counter = AUTOTUNE_SUCCESS_COUNT;
1446
// reset variables for next test
1447
next_freq = 0.0f; //initializes next test that uses dwell test
1448
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max rate P freq=%f gain=%f", (double)(max_rate_p.freq), (double)(max_rate_p.gain));
1449
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_p=%f", (double)(max_rate_p.phase), (double)(max_rate_p.max_allowed));
1450
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Max Rate D freq=%f gain=%f", (double)(max_rate_d.freq), (double)(max_rate_d.gain));
1451
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_d=%f", (double)(max_rate_d.phase), (double)(max_rate_d.max_allowed));
1452
}
1453
1454
}
1455
1456
float AC_AutoTune_Heli::target_angle_max_rp_cd() const
1457
{
1458
return AUTOTUNE_ANGLE_TARGET_MAX_RP_CD;
1459
}
1460
1461
float AC_AutoTune_Heli::target_angle_max_y_cd() const
1462
{
1463
return AUTOTUNE_ANGLE_TARGET_MAX_Y_CD;
1464
}
1465
1466
float AC_AutoTune_Heli::target_angle_min_rp_cd() const
1467
{
1468
return AUTOTUNE_ANGLE_TARGET_MIN_RP_CD;
1469
}
1470
1471
float AC_AutoTune_Heli::target_angle_min_y_cd() const
1472
{
1473
return AUTOTUNE_ANGLE_TARGET_MIN_Y_CD;
1474
}
1475
1476
float AC_AutoTune_Heli::angle_lim_max_rp_cd() const
1477
{
1478
return AUTOTUNE_ANGLE_MAX_RP_CD;
1479
}
1480
1481
float AC_AutoTune_Heli::angle_lim_neg_rpy_cd() const
1482
{
1483
return AUTOTUNE_ANGLE_NEG_RPY_CD;
1484
}
1485
1486
// freq_search_for_phase: general search strategy for specified phase. interpolation done once specified phase has been bounded.
1487
bool AC_AutoTune_Heli::freq_search_for_phase(sweep_info test, float desired_phase, float freq_incr, sweep_info &est_data, float &new_freq)
1488
{
1489
new_freq = test.freq;
1490
float phase_delta = 20.0f; // delta from desired phase below and above which full steps are taken
1491
if (is_zero(test.phase)) {
1492
// bad test point. increase slightly in hope of getting better result
1493
new_freq += 0.1f * freq_incr;
1494
return false;
1495
}
1496
1497
// test to see if desired phase is bounded with a 0.5 freq_incr delta in freq
1498
float freq_delta = fabsf(prev_test.freq - test.freq);
1499
if (test.phase > desired_phase && prev_test.phase < desired_phase && freq_delta < 0.75f * freq_incr && is_positive(prev_test.freq)) {
1500
est_data.freq = linear_interpolate(prev_test.freq,test.freq,desired_phase,prev_test.phase,test.phase);
1501
est_data.gain = linear_interpolate(prev_test.gain,test.gain,desired_phase,prev_test.phase,test.phase);
1502
est_data.phase = desired_phase;
1503
prev_test = {};
1504
return true;
1505
} else if (test.phase < desired_phase && prev_test.phase > desired_phase && freq_delta < 0.75f * freq_incr && is_positive(prev_test.freq)) {
1506
est_data.freq = linear_interpolate(test.freq,prev_test.freq,desired_phase,test.phase,prev_test.phase);
1507
est_data.gain = linear_interpolate(test.gain,prev_test.gain,desired_phase,test.phase,prev_test.phase);
1508
est_data.phase = desired_phase;
1509
prev_test = {};
1510
return true;
1511
}
1512
1513
if (test.phase < desired_phase - phase_delta) {
1514
new_freq += freq_incr;
1515
} else if (test.phase > desired_phase + phase_delta) {
1516
new_freq -= freq_incr;
1517
} else if (test.phase >= desired_phase - phase_delta && test.phase < desired_phase) {
1518
new_freq += 0.5f * freq_incr;
1519
} else if (test.phase <= desired_phase + phase_delta && test.phase >= desired_phase) {
1520
new_freq -= 0.5f * freq_incr;
1521
}
1522
prev_test = test;
1523
return false;
1524
}
1525
1526
#if HAL_LOGGING_ENABLED
1527
// log autotune summary data
1528
void AC_AutoTune_Heli::Log_AutoTune()
1529
{
1530
1531
switch (axis) {
1532
case AxisType::ROLL:
1533
Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_roll_rff, tune_roll_rp, tune_roll_rd, tune_roll_sp, test_accel_max);
1534
break;
1535
case AxisType::PITCH:
1536
Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_pitch_rff, tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, test_accel_max);
1537
break;
1538
case AxisType::YAW:
1539
case AxisType::YAW_D:
1540
Log_Write_AutoTune(axis, tune_type, curr_data.freq, curr_data.gain, curr_data.phase, tune_yaw_rff, tune_yaw_rp, tune_yaw_rd, tune_yaw_sp, test_accel_max);
1541
break;
1542
}
1543
}
1544
1545
// log autotune time history results for command, angular rate, and attitude
1546
void AC_AutoTune_Heli::Log_AutoTuneDetails()
1547
{
1548
if (tune_type == SP_UP || tune_type == TUNE_CHECK) {
1549
Log_Write_AutoTuneDetails(command_out, 0.0f, 0.0f, filt_target_rate, rotation_rate);
1550
} else {
1551
Log_Write_AutoTuneDetails(command_out, filt_target_rate, rotation_rate, 0.0f, 0.0f);
1552
}
1553
}
1554
1555
// log autotune frequency response data
1556
void AC_AutoTune_Heli::Log_AutoTuneSweep()
1557
{
1558
Log_Write_AutoTuneSweep(curr_test_mtr.freq, curr_test_mtr.gain, curr_test_mtr.phase,curr_test_tgt.freq, curr_test_tgt.gain, curr_test_tgt.phase);
1559
}
1560
1561
// @LoggerMessage: ATNH
1562
// @Description: Heli AutoTune
1563
// @Vehicles: Copter
1564
// @Field: TimeUS: Time since system startup
1565
// @Field: Axis: which axis is currently being tuned
1566
// @Field: TuneStep: step in autotune process
1567
// @Field: Freq: target dwell frequency
1568
// @Field: Gain: measured gain of dwell
1569
// @Field: Phase: measured phase of dwell
1570
// @Field: RFF: new rate gain FF term
1571
// @Field: RP: new rate gain P term
1572
// @Field: RD: new rate gain D term
1573
// @Field: SP: new angle P term
1574
// @Field: ACC: new max accel term
1575
1576
// Write an Autotune summary data packet
1577
void AC_AutoTune_Heli::Log_Write_AutoTune(AxisType _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel)
1578
{
1579
AP::logger().Write(
1580
"ATNH",
1581
"TimeUS,Axis,TuneStep,Freq,Gain,Phase,RFF,RP,RD,SP,ACC",
1582
"s--E-d-----",
1583
"F--000-----",
1584
"QBBffffffff",
1585
AP_HAL::micros64(),
1586
(uint8_t)axis,
1587
tune_step,
1588
dwell_freq,
1589
meas_gain,
1590
meas_phase,
1591
new_gain_rff,
1592
new_gain_rp,
1593
new_gain_rd,
1594
new_gain_sp,
1595
max_accel);
1596
}
1597
1598
// Write an Autotune detailed data packet
1599
void AC_AutoTune_Heli::Log_Write_AutoTuneDetails(float motor_cmd, float tgt_rate_rads, float rate_rads, float tgt_ang_rad, float ang_rad)
1600
{
1601
// @LoggerMessage: ATDH
1602
// @Description: Heli AutoTune data packet
1603
// @Vehicles: Copter
1604
// @Field: TimeUS: Time since system startup
1605
// @Field: Cmd: current motor command
1606
// @Field: TRate: current target angular rate
1607
// @Field: Rate: current angular rate
1608
// @Field: TAng: current target angle
1609
// @Field: Ang: current angle
1610
AP::logger().WriteStreaming(
1611
"ATDH",
1612
"TimeUS,Cmd,TRate,Rate,TAng,Ang",
1613
"s-kkdd",
1614
"F00000",
1615
"Qfffff",
1616
AP_HAL::micros64(),
1617
motor_cmd,
1618
tgt_rate_rads*57.3,
1619
rate_rads*57.3f,
1620
tgt_ang_rad*57.3,
1621
ang_rad*57.3f);
1622
}
1623
1624
// Write an Autotune frequency response data packet
1625
void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq_mtr, float gain_mtr, float phase_mtr, float freq_tgt, float gain_tgt, float phase_tgt)
1626
{
1627
// @LoggerMessage: ATSH
1628
// @Description: Heli AutoTune Sweep packet
1629
// @Vehicles: Copter
1630
// @Field: TimeUS: Time since system startup
1631
// @Field: freq_m: current frequency for motor input to rate
1632
// @Field: gain_m: current response gain for motor input to rate
1633
// @Field: phase_m: current response phase for motor input to rate
1634
// @Field: freq_t: current frequency for target rate to rate
1635
// @Field: gain_t: current response gain for target rate to rate
1636
// @Field: phase_t: current response phase for target rate to rate
1637
AP::logger().WriteStreaming(
1638
"ATSH",
1639
"TimeUS,freq_m,gain_m,phase_m,freq_t,gain_t,phase_t",
1640
"sE-dE-d",
1641
"F000000",
1642
"Qffffff",
1643
AP_HAL::micros64(),
1644
freq_mtr,
1645
gain_mtr,
1646
phase_mtr,
1647
freq_tgt,
1648
gain_tgt,
1649
phase_tgt);
1650
}
1651
#endif // HAL_LOGGING_ENABLED
1652
1653
// reset the test variables for each vehicle
1654
void AC_AutoTune_Heli::reset_vehicle_test_variables()
1655
{
1656
// reset dwell test variables if sweep was interrupted in order to restart sweep
1657
if (!is_equal(start_freq, stop_freq)) {
1658
start_freq = 0.0f;
1659
stop_freq = 0.0f;
1660
next_test_freq = 0.0f;
1661
sweep_complete = false;
1662
}
1663
}
1664
1665
// reset the update gain variables for heli
1666
void AC_AutoTune_Heli::reset_update_gain_variables()
1667
{
1668
// reset max gain variables
1669
reset_maxgains_update_gain_variables();
1670
1671
// reset rd_up variables
1672
rd_prev_gain = 0.0f;
1673
1674
// reset sp_up variables
1675
phase_max = 0.0f;
1676
freq_max = 0.0f;
1677
sp_prev_gain = 0.0f;
1678
found_max_gain_freq = false;
1679
found_peak = false;
1680
1681
}
1682
1683
// reset the max_gains update gain variables
1684
void AC_AutoTune_Heli::reset_maxgains_update_gain_variables()
1685
{
1686
max_rate_p = {};
1687
max_rate_d = {};
1688
1689
found_max_p = false;
1690
found_max_d = false;
1691
1692
}
1693
1694
// reset the max_gains update gain variables
1695
void AC_AutoTune_Heli::reset_sweep_variables()
1696
{
1697
sweep_tgt.ph180 = {};
1698
sweep_tgt.ph270 = {};
1699
sweep_tgt.maxgain = {};
1700
sweep_tgt.progress = 0;
1701
1702
sweep_mtr.ph180 = {};
1703
sweep_mtr.ph270 = {};
1704
sweep_mtr.maxgain = {};
1705
1706
sweep_mtr.progress = 0;
1707
1708
}
1709
1710
// set the tuning test sequence
1711
void AC_AutoTune_Heli::set_tune_sequence()
1712
{
1713
uint8_t seq_cnt = 0;
1714
1715
if (seq_bitmask & AUTOTUNE_SEQ_BITMASK_VFF) {
1716
tune_seq[seq_cnt] = RFF_UP;
1717
seq_cnt++;
1718
}
1719
if (seq_bitmask & AUTOTUNE_SEQ_BITMASK_RATE_D) {
1720
tune_seq[seq_cnt] = MAX_GAINS;
1721
seq_cnt++;
1722
tune_seq[seq_cnt] = RD_UP;
1723
seq_cnt++;
1724
tune_seq[seq_cnt] = RP_UP;
1725
seq_cnt++;
1726
}
1727
if (seq_bitmask & AUTOTUNE_SEQ_BITMASK_ANGLE_P) {
1728
tune_seq[seq_cnt] = SP_UP;
1729
seq_cnt++;
1730
}
1731
if (seq_bitmask & AUTOTUNE_SEQ_BITMASK_MAX_GAIN && !(seq_bitmask & AUTOTUNE_SEQ_BITMASK_RATE_D)) {
1732
tune_seq[seq_cnt] = MAX_GAINS;
1733
seq_cnt++;
1734
}
1735
if (seq_bitmask & AUTOTUNE_SEQ_BITMASK_TUNE_CHECK) {
1736
tune_seq[seq_cnt] = TUNE_CHECK;
1737
seq_cnt++;
1738
}
1739
tune_seq[seq_cnt] = TUNE_COMPLETE;
1740
1741
}
1742
1743
// get_testing_step_timeout_ms accessor
1744
uint32_t AC_AutoTune_Heli::get_testing_step_timeout_ms() const
1745
{
1746
return AUTOTUNE_TESTING_STEP_TIMEOUT_MS;
1747
}
1748
1749
// exceeded_freq_range - ensures tuning remains inside frequency range
1750
bool AC_AutoTune_Heli::exceeded_freq_range(float frequency)
1751
{
1752
bool ret = false;
1753
if (frequency < min_sweep_freq || frequency > max_sweep_freq) {
1754
ret = true;
1755
}
1756
return ret;
1757
}
1758
1759
#endif // AC_AUTOTUNE_ENABLED
1760
1761