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.cpp
Views: 1798
1
#include "AC_AutoTune_config.h"
2
3
#if AC_AUTOTUNE_ENABLED
4
5
#include "AC_AutoTune.h"
6
7
#include <AP_Logger/AP_Logger.h>
8
#include <AP_Scheduler/AP_Scheduler.h>
9
#include <AP_Notify/AP_Notify.h>
10
#include <GCS_MAVLink/GCS.h>
11
#include <AP_Vehicle/AP_Vehicle_Type.h>
12
13
#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
14
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
15
# define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg)
16
# define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec)
17
#else
18
# define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level
19
# define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch
20
#endif
21
#define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
22
#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 250 // time we require the aircraft to be level before starting next test
23
#define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level
24
#define AUTOTUNE_LEVEL_WARNING_INTERVAL_MS 5000 // level failure warning messages sent at this interval to users
25
26
AC_AutoTune::AC_AutoTune()
27
{
28
}
29
30
// autotune_init - should be called when autotune mode is selected
31
bool AC_AutoTune::init_internals(bool _use_poshold,
32
AC_AttitudeControl *_attitude_control,
33
AC_PosControl *_pos_control,
34
AP_AHRS_View *_ahrs_view,
35
AP_InertialNav *_inertial_nav)
36
{
37
use_poshold = _use_poshold;
38
attitude_control = _attitude_control;
39
pos_control = _pos_control;
40
ahrs_view = _ahrs_view;
41
inertial_nav = _inertial_nav;
42
motors = AP_Motors::get_singleton();
43
const uint32_t now = AP_HAL::millis();
44
45
// exit immediately if motor are not armed
46
if ((motors == nullptr) || !motors->armed()) {
47
return false;
48
}
49
50
// initialise position controller
51
init_position_controller();
52
53
switch (mode) {
54
case FAILED:
55
// fall through to restart the tuning
56
FALLTHROUGH;
57
58
case UNINITIALISED:
59
// autotune has never been run
60
// so store current gains as original gains
61
backup_gains_and_initialise();
62
// advance mode to tuning
63
mode = TUNING;
64
// send message to ground station that we've started tuning
65
update_gcs(AUTOTUNE_MESSAGE_STARTED);
66
break;
67
68
case TUNING:
69
// reset test variables for each vehicle
70
reset_vehicle_test_variables();
71
72
// we are restarting tuning so restart where we left off
73
step = WAITING_FOR_LEVEL;
74
step_start_time_ms = now;
75
level_start_time_ms = now;
76
// reset gains to tuning-start gains (i.e. low I term)
77
load_gains(GAIN_INTRA_TEST);
78
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART);
79
update_gcs(AUTOTUNE_MESSAGE_STARTED);
80
break;
81
82
case SUCCESS:
83
// we have completed a tune and the pilot wishes to test the new gains
84
load_gains(GAIN_TUNED);
85
update_gcs(AUTOTUNE_MESSAGE_TESTING);
86
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_PILOT_TESTING);
87
break;
88
}
89
90
have_position = false;
91
92
return true;
93
}
94
95
// stop - should be called when the ch7/ch8 switch is switched OFF
96
void AC_AutoTune::stop()
97
{
98
// set gains to their original values
99
load_gains(GAIN_ORIGINAL);
100
101
// re-enable angle-to-rate request limits
102
attitude_control->use_sqrt_controller(true);
103
104
update_gcs(AUTOTUNE_MESSAGE_STOPPED);
105
106
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_OFF);
107
108
// Note: we leave the mode as it was so that we know how the autotune ended
109
// we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch
110
}
111
112
// Autotune aux function trigger
113
void AC_AutoTune::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)
114
{
115
if (mode != TuneMode::SUCCESS) {
116
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
117
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: must be complete to test gains");
118
}
119
return;
120
}
121
122
switch(ch_flag) {
123
case RC_Channel::AuxSwitchPos::LOW:
124
// load original gains
125
load_gains(GainType::GAIN_ORIGINAL);
126
update_gcs(AUTOTUNE_MESSAGE_TESTING_END);
127
break;
128
case RC_Channel::AuxSwitchPos::MIDDLE:
129
// Middle position is unused for now
130
break;
131
case RC_Channel::AuxSwitchPos::HIGH:
132
// Load tuned gains
133
load_gains(GainType::GAIN_TUNED);
134
update_gcs(AUTOTUNE_MESSAGE_TESTING);
135
break;
136
}
137
138
have_pilot_testing_command = true;
139
}
140
141
// Possibly save gains, called on disarm
142
void AC_AutoTune::disarmed(const bool in_autotune_mode)
143
{
144
// True if pilot is testing tuned gains
145
const bool testing_tuned = have_pilot_testing_command && (loaded_gains == GainType::GAIN_TUNED);
146
147
// True if in autotune mode and no pilot testing commands have been received
148
const bool tune_complete_no_testing = !have_pilot_testing_command && in_autotune_mode;
149
150
if (tune_complete_no_testing || testing_tuned) {
151
save_tuning_gains();
152
} else {
153
reset();
154
}
155
}
156
157
// initialise position controller
158
bool AC_AutoTune::init_position_controller(void)
159
{
160
// initialize vertical maximum speeds and acceleration
161
init_z_limits();
162
163
// initialise the vertical position controller
164
pos_control->init_z_controller();
165
166
return true;
167
}
168
169
void AC_AutoTune::send_step_string()
170
{
171
if (pilot_override) {
172
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
173
return;
174
}
175
switch (step) {
176
case WAITING_FOR_LEVEL:
177
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Leveling");
178
return;
179
case UPDATE_GAINS:
180
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Updating Gains");
181
return;
182
case ABORT:
183
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Aborting Test");
184
return;
185
case TESTING:
186
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Testing");
187
return;
188
}
189
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: unknown step");
190
}
191
192
const char *AC_AutoTune::type_string() const
193
{
194
switch (tune_type) {
195
case RD_UP:
196
return "Rate D Up";
197
case RD_DOWN:
198
return "Rate D Down";
199
case RP_UP:
200
return "Rate P Up";
201
case RFF_UP:
202
return "Rate FF Up";
203
case SP_UP:
204
return "Angle P Up";
205
case SP_DOWN:
206
return "Angle P Down";
207
case MAX_GAINS:
208
return "Find Max Gains";
209
case TUNE_CHECK:
210
return "Check Tune Frequency Response";
211
case TUNE_COMPLETE:
212
return "Tune Complete";
213
}
214
return "";
215
// this should never happen
216
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
217
}
218
219
// return current axis string
220
const char *AC_AutoTune::axis_string() const
221
{
222
switch (axis) {
223
case AxisType::ROLL:
224
return "Roll";
225
case AxisType::PITCH:
226
return "Pitch";
227
case AxisType::YAW:
228
return "Yaw(E)";
229
case AxisType::YAW_D:
230
return "Yaw(D)";
231
}
232
return "";
233
}
234
235
// run - runs the autotune flight mode
236
// should be called at 100hz or more
237
void AC_AutoTune::run()
238
{
239
// initialize vertical speeds and acceleration
240
init_z_limits();
241
242
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
243
// this should not actually be possible because of the init() checks
244
if (!motors->armed() || !motors->get_interlock()) {
245
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
246
attitude_control->set_throttle_out(0.0f, true, 0.0f);
247
pos_control->relax_z_controller(0.0f);
248
return;
249
}
250
251
float target_roll_cd, target_pitch_cd, target_yaw_rate_cds;
252
get_pilot_desired_rp_yrate_cd(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
253
254
// get pilot desired climb rate
255
const float target_climb_rate_cms = get_pilot_desired_climb_rate_cms();
256
257
const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd);
258
259
const uint32_t now = AP_HAL::millis();
260
261
if (mode != SUCCESS) {
262
if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) {
263
if (!pilot_override) {
264
pilot_override = true;
265
// set gains to their original values
266
load_gains(GAIN_ORIGINAL);
267
attitude_control->use_sqrt_controller(true);
268
}
269
// reset pilot override time
270
override_time = now;
271
if (!zero_rp_input) {
272
// only reset position on roll or pitch input
273
have_position = false;
274
}
275
} else if (pilot_override) {
276
// check if we should resume tuning after pilot's override
277
if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {
278
pilot_override = false; // turn off pilot override
279
// set gains to their intra-test values (which are very close to the original gains)
280
// load_gains(GAIN_INTRA_TEST); //I think we should be keeping the originals here to let the I term settle quickly
281
step = WAITING_FOR_LEVEL; // set tuning step back from beginning
282
step_start_time_ms = now;
283
level_start_time_ms = now;
284
desired_yaw_cd = ahrs_view->yaw_sensor;
285
}
286
}
287
}
288
if (pilot_override) {
289
if (now - last_pilot_override_warning > 1000) {
290
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active");
291
last_pilot_override_warning = now;
292
}
293
}
294
if (zero_rp_input) {
295
// pilot input on throttle and yaw will still use position hold if enabled
296
get_poshold_attitude(target_roll_cd, target_pitch_cd, desired_yaw_cd);
297
}
298
299
// set motors to full range
300
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
301
302
// if pilot override call attitude controller
303
if (pilot_override || mode != TUNING) {
304
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll_cd, target_pitch_cd, target_yaw_rate_cds);
305
} else {
306
// somehow get attitude requests from autotuning
307
control_attitude();
308
// tell the user what's going on
309
do_gcs_announcements();
310
}
311
312
// call position controller
313
pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cms);
314
pos_control->update_z_controller();
315
316
}
317
318
// return true if vehicle is close to level
319
bool AC_AutoTune::currently_level()
320
{
321
// abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS
322
const uint32_t now_ms = AP_HAL::millis();
323
if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) {
324
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually");
325
mode = FAILED;
326
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
327
}
328
329
// slew threshold to ensure sufficient settling time for aircraft unable to obtain small thresholds
330
// relax threshold if we pass AUTOTUNE_LEVEL_TIMEOUT_MS
331
const float threshold_mul = constrain_float((float)(now_ms - level_start_time_ms) / (float)AUTOTUNE_LEVEL_TIMEOUT_MS, 0.0, 2.0);
332
333
if (fabsf(ahrs_view->roll_sensor - roll_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {
334
return false;
335
}
336
337
if (fabsf(ahrs_view->pitch_sensor - pitch_cd) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {
338
return false;
339
}
340
if (fabsf(wrap_180_cd(ahrs_view->yaw_sensor - desired_yaw_cd)) > threshold_mul * AUTOTUNE_LEVEL_ANGLE_CD) {
341
return false;
342
}
343
if ((ToDeg(ahrs_view->get_gyro().x) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) {
344
return false;
345
}
346
if ((ToDeg(ahrs_view->get_gyro().y) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_RP_CD) {
347
return false;
348
}
349
if ((ToDeg(ahrs_view->get_gyro().z) * 100.0f) > threshold_mul * AUTOTUNE_LEVEL_RATE_Y_CD) {
350
return false;
351
}
352
return true;
353
}
354
355
// main state machine to level vehicle, perform a test and update gains
356
// directly updates attitude controller with targets
357
void AC_AutoTune::control_attitude()
358
{
359
rotation_rate = 0.0f; // rotation rate in radians/second
360
lean_angle = 0.0f;
361
const float direction_sign = positive_direction ? 1.0f : -1.0f;
362
const uint32_t now = AP_HAL::millis();
363
364
// check tuning step
365
switch (step) {
366
367
case WAITING_FOR_LEVEL: {
368
369
// Note: we should be using intra-test gains (which are very close to the original gains but have lower I)
370
// re-enable rate limits
371
attitude_control->use_sqrt_controller(true);
372
373
get_poshold_attitude(roll_cd, pitch_cd, desired_yaw_cd);
374
375
// hold level attitude
376
attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);
377
378
// hold the copter level for 0.5 seconds before we begin a twitch
379
// reset counter if we are no longer level
380
if (!currently_level()) {
381
step_start_time_ms = now;
382
}
383
384
// if we have been level for a sufficient amount of time (0.5 seconds) move onto tuning step
385
if (now - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {
386
// initiate variables for next step
387
step = TESTING;
388
step_start_time_ms = now;
389
step_time_limit_ms = get_testing_step_timeout_ms();
390
// set gains to their to-be-tested values
391
load_gains(GAIN_TEST);
392
} else {
393
// when waiting for level we use the intra-test gains
394
load_gains(GAIN_INTRA_TEST);
395
}
396
397
// Initialize test-specific variables
398
switch (axis) {
399
case AxisType::ROLL:
400
start_rate = ToDeg(ahrs_view->get_gyro().x) * 100.0f;
401
start_angle = ahrs_view->roll_sensor;
402
break;
403
case AxisType::PITCH:
404
start_rate = ToDeg(ahrs_view->get_gyro().y) * 100.0f;
405
start_angle = ahrs_view->pitch_sensor;
406
break;
407
case AxisType::YAW:
408
case AxisType::YAW_D:
409
start_rate = ToDeg(ahrs_view->get_gyro().z) * 100.0f;
410
start_angle = ahrs_view->yaw_sensor;
411
break;
412
}
413
414
// tests must be initialized last as some rely on variables above
415
test_init();
416
417
break;
418
}
419
420
case TESTING: {
421
// Run the twitching step
422
load_gains(GAIN_TEST);
423
424
// run the test
425
test_run(axis, direction_sign);
426
427
// Check for failure causing reverse response
428
if (lean_angle <= -angle_lim_neg_rpy_cd()) {
429
step = WAITING_FOR_LEVEL;
430
positive_direction = twitch_reverse_direction();
431
step_start_time_ms = now;
432
level_start_time_ms = now;
433
}
434
435
// protect from roll over
436
if (attitude_control->lean_angle_deg() * 100 > angle_lim_max_rp_cd()) {
437
step = WAITING_FOR_LEVEL;
438
positive_direction = twitch_reverse_direction();
439
step_start_time_ms = now;
440
level_start_time_ms = now;
441
}
442
443
#if HAL_LOGGING_ENABLED
444
// log this iterations lean angle and rotation rate
445
Log_AutoTuneDetails();
446
attitude_control->Write_Rate(*pos_control);
447
log_pids();
448
#endif
449
450
if (axis == AxisType::YAW || axis == AxisType::YAW_D) {
451
desired_yaw_cd = ahrs_view->yaw_sensor;
452
}
453
break;
454
}
455
456
case UPDATE_GAINS:
457
458
// re-enable rate limits
459
attitude_control->use_sqrt_controller(true);
460
461
#if HAL_LOGGING_ENABLED
462
// log the latest gains
463
Log_AutoTune();
464
#endif
465
466
// Announce tune type test results
467
// must be done before updating method because this method changes parameters for next test
468
do_post_test_gcs_announcements();
469
470
switch (tune_type) {
471
// Check results after mini-step to increase rate D gain
472
case RD_UP:
473
updating_rate_d_up_all(axis);
474
break;
475
// Check results after mini-step to decrease rate D gain
476
case RD_DOWN:
477
updating_rate_d_down_all(axis);
478
break;
479
// Check results after mini-step to increase rate P gain
480
case RP_UP:
481
updating_rate_p_up_all(axis);
482
break;
483
// Check results after mini-step to increase stabilize P gain
484
case SP_DOWN:
485
updating_angle_p_down_all(axis);
486
break;
487
// Check results after mini-step to increase stabilize P gain
488
case SP_UP:
489
updating_angle_p_up_all(axis);
490
break;
491
case RFF_UP:
492
updating_rate_ff_up_all(axis);
493
break;
494
case MAX_GAINS:
495
updating_max_gains_all(axis);
496
break;
497
case TUNE_CHECK:
498
counter = AUTOTUNE_SUCCESS_COUNT;
499
FALLTHROUGH;
500
case TUNE_COMPLETE:
501
break;
502
}
503
504
// we've complete this step, finalize pids and move to next step
505
if (counter >= AUTOTUNE_SUCCESS_COUNT) {
506
507
// reset counter
508
counter = 0;
509
510
// reset scaling factor
511
step_scaler = 1.0f;
512
513
514
// set gains for post tune before moving to the next tuning type
515
set_gains_post_tune(axis);
516
517
// increment the tune type to the next one in tune sequence
518
next_tune_type(tune_type, false);
519
520
if (tune_type == TUNE_COMPLETE) {
521
// we've reached the end of a D-up-down PI-up-down tune type cycle
522
next_tune_type(tune_type, true);
523
524
report_final_gains(axis);
525
526
// advance to the next axis
527
bool complete = false;
528
switch (axis) {
529
case AxisType::ROLL:
530
axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;
531
if (pitch_enabled()) {
532
axis = AxisType::PITCH;
533
} else if (yaw_enabled()) {
534
axis = AxisType::YAW;
535
} else if (yaw_d_enabled()) {
536
axis = AxisType::YAW_D;
537
} else {
538
complete = true;
539
}
540
break;
541
case AxisType::PITCH:
542
axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;
543
if (yaw_enabled()) {
544
axis = AxisType::YAW;
545
} else if (yaw_d_enabled()) {
546
axis = AxisType::YAW_D;
547
} else {
548
complete = true;
549
}
550
break;
551
case AxisType::YAW:
552
axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;
553
if (yaw_d_enabled()) {
554
axis = AxisType::YAW_D;
555
} else {
556
complete = true;
557
}
558
break;
559
case AxisType::YAW_D:
560
axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW_D;
561
complete = true;
562
break;
563
}
564
565
// if we've just completed all axes we have successfully completed the autotune
566
// change to TESTING mode to allow user to fly with new gains
567
if (complete) {
568
mode = SUCCESS;
569
update_gcs(AUTOTUNE_MESSAGE_SUCCESS);
570
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS);
571
AP_Notify::events.autotune_complete = true;
572
573
// Return to original gains for landing
574
load_gains(GainType::GAIN_ORIGINAL);
575
} else {
576
AP_Notify::events.autotune_next_axis = true;
577
reset_update_gain_variables();
578
}
579
}
580
}
581
FALLTHROUGH;
582
583
case ABORT:
584
if (axis == AxisType::YAW || axis == AxisType::YAW_D) {
585
// todo: check to make sure we need this
586
attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs_view->yaw_sensor, false);
587
}
588
589
// set gains to their intra-test values (which are very close to the original gains)
590
load_gains(GAIN_INTRA_TEST);
591
592
// reset testing step
593
step = WAITING_FOR_LEVEL;
594
positive_direction = twitch_reverse_direction();
595
step_start_time_ms = now;
596
level_start_time_ms = now;
597
step_time_limit_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;
598
break;
599
}
600
}
601
602
// backup_gains_and_initialise - store current gains as originals
603
// called before tuning starts to backup original gains
604
void AC_AutoTune::backup_gains_and_initialise()
605
{
606
const uint32_t now = AP_HAL::millis();
607
608
// initialise state because this is our first time
609
if (roll_enabled()) {
610
axis = AxisType::ROLL;
611
} else if (pitch_enabled()) {
612
axis = AxisType::PITCH;
613
} else if (yaw_enabled()) {
614
axis = AxisType::YAW;
615
} else if (yaw_d_enabled()) {
616
axis = AxisType::YAW_D;
617
}
618
// no axes are complete
619
axes_completed = 0;
620
621
// reset update gain variables for each vehicle
622
reset_update_gain_variables();
623
624
// start at the beginning of tune sequence
625
next_tune_type(tune_type, true);
626
627
step = WAITING_FOR_LEVEL;
628
positive_direction = false;
629
step_start_time_ms = now;
630
level_start_time_ms = now;
631
step_scaler = 1.0f;
632
633
desired_yaw_cd = ahrs_view->yaw_sensor;
634
}
635
636
/*
637
load a specified set of gains
638
*/
639
void AC_AutoTune::load_gains(enum GainType gain_type)
640
{
641
if (loaded_gains == gain_type) {
642
// Loaded gains are already of correct type
643
return;
644
}
645
loaded_gains = gain_type;
646
647
switch (gain_type) {
648
case GAIN_ORIGINAL:
649
load_orig_gains();
650
break;
651
case GAIN_INTRA_TEST:
652
load_intra_test_gains();
653
break;
654
case GAIN_TEST:
655
load_test_gains();
656
break;
657
case GAIN_TUNED:
658
load_tuned_gains();
659
break;
660
}
661
}
662
663
// update_gcs - send message to ground station
664
void AC_AutoTune::update_gcs(uint8_t message_id) const
665
{
666
switch (message_id) {
667
case AUTOTUNE_MESSAGE_STARTED:
668
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Started");
669
break;
670
case AUTOTUNE_MESSAGE_STOPPED:
671
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Stopped");
672
break;
673
case AUTOTUNE_MESSAGE_SUCCESS:
674
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Success");
675
break;
676
case AUTOTUNE_MESSAGE_FAILED:
677
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
678
break;
679
case AUTOTUNE_MESSAGE_TESTING:
680
case AUTOTUNE_MESSAGE_SAVED_GAINS:
681
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s gains for %s%s%s%s",
682
(message_id == AUTOTUNE_MESSAGE_SAVED_GAINS) ? "Saved" : "Pilot Testing",
683
(axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",
684
(axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",
685
(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw(E)":"",
686
(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW_D)?"Yaw(D)":"");
687
break;
688
case AUTOTUNE_MESSAGE_TESTING_END:
689
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: original gains restored");
690
break;
691
}
692
}
693
694
// axis helper functions
695
bool AC_AutoTune::roll_enabled() const
696
{
697
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_ROLL;
698
}
699
700
bool AC_AutoTune::pitch_enabled() const
701
{
702
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_PITCH;
703
}
704
705
bool AC_AutoTune::yaw_enabled() const
706
{
707
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW;
708
}
709
710
bool AC_AutoTune::yaw_d_enabled() const
711
{
712
#if APM_BUILD_TYPE(APM_BUILD_Heli)
713
return false;
714
#else
715
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW_D;
716
#endif
717
}
718
719
/*
720
check if we have a good position estimate
721
*/
722
bool AC_AutoTune::position_ok(void)
723
{
724
if (!AP::ahrs().have_inertial_nav()) {
725
// do not allow navigation with dcm position
726
return false;
727
}
728
729
// with EKF use filter status and ekf check
730
nav_filter_status filt_status = inertial_nav->get_filter_status();
731
732
// require a good absolute position and EKF must not be in const_pos_mode
733
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
734
}
735
736
// get attitude for slow position hold in autotune mode
737
void AC_AutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)
738
{
739
roll_cd_out = pitch_cd_out = 0;
740
741
if (!use_poshold) {
742
// we are not trying to hold position
743
return;
744
}
745
746
// do we know where we are? If not then don't do poshold
747
if (!position_ok()) {
748
return;
749
}
750
751
if (!have_position) {
752
have_position = true;
753
start_position = inertial_nav->get_position_neu_cm();
754
}
755
756
// don't go past 10 degrees, as autotune result would deteriorate too much
757
const float angle_max_cd = 1000;
758
759
// hit the 10 degree limit at 20 meters position error
760
const float dist_limit_cm = 2000;
761
762
// we only start adjusting yaw if we are more than 5m from the
763
// target position. That corresponds to a lean angle of 2.5 degrees
764
const float yaw_dist_limit_cm = 500;
765
766
Vector3f pdiff = inertial_nav->get_position_neu_cm() - start_position;
767
pdiff.z = 0;
768
float dist_cm = pdiff.length();
769
if (dist_cm < 10) {
770
// don't do anything within 10cm
771
return;
772
}
773
774
/*
775
very simple linear controller
776
*/
777
float scaling = constrain_float(angle_max_cd * dist_cm / dist_limit_cm, 0, angle_max_cd);
778
Vector2f angle_ne(pdiff.x, pdiff.y);
779
angle_ne *= scaling / dist_cm;
780
781
// rotate into body frame
782
pitch_cd_out = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();
783
roll_cd_out = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();
784
785
if (dist_cm < yaw_dist_limit_cm) {
786
// no yaw adjustment
787
return;
788
}
789
790
/*
791
also point so that twitching occurs perpendicular to the wind,
792
if we have drifted more than yaw_dist_limit_cm from the desired
793
position. This ensures that autotune doesn't have to deal with
794
more than 2.5 degrees of attitude on the axis it is tuning
795
*/
796
float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100;
797
if (axis == AxisType::PITCH) {
798
// for roll and yaw tuning we point along the wind, for pitch
799
// we point across the wind
800
target_yaw_cd += 9000;
801
}
802
// go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation
803
if (fabsf(yaw_cd_out - target_yaw_cd) > 9500) {
804
target_yaw_cd += 18000;
805
}
806
807
yaw_cd_out = target_yaw_cd;
808
}
809
810
// get the next tune type
811
void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)
812
{
813
if (reset) {
814
set_tune_sequence();
815
tune_seq_curr = 0;
816
} else if (curr_tune_type == TUNE_COMPLETE) {
817
// leave tune_type as TUNE_COMPLETE to initiate next axis or exit autotune
818
return;
819
} else {
820
tune_seq_curr++;
821
}
822
823
curr_tune_type = tune_seq[tune_seq_curr];
824
}
825
826
#endif // AC_AUTOTUNE_ENABLED
827
828