Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AutoTune/AC_AutoTune.cpp
9447 views
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
{
36
use_poshold = _use_poshold;
37
attitude_control = _attitude_control;
38
pos_control = _pos_control;
39
ahrs_view = _ahrs_view;
40
motors = AP_Motors::get_singleton();
41
const uint32_t now_ms = AP_HAL::millis();
42
43
// exit immediately if motor are not armed
44
if ((motors == nullptr) || !motors->armed()) {
45
return false;
46
}
47
48
// initialise position controller
49
init_position_controller();
50
51
switch (mode) {
52
case TuneMode::FAILED:
53
// Fall through to restart the tuning process from scratch
54
FALLTHROUGH;
55
56
case TuneMode::UNINITIALISED:
57
// First-time run: store the current gains as the baseline (original gains)
58
backup_gains_and_initialise();
59
// Set the mode to TUNING to begin the autotune process
60
mode = TuneMode::TUNING;
61
// Notify GCS that autotune has started
62
update_gcs(AUTOTUNE_MESSAGE_STARTED);
63
break;
64
65
case TuneMode::TUNING:
66
// Resuming from previous tuning session, restart from current axis and tune step
67
reset_vehicle_test_variables();
68
step = Step::WAITING_FOR_LEVEL;
69
step_start_time_ms = now_ms;
70
level_start_time_ms = now_ms;
71
// Reload gains with low I-term and restart logging
72
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART);
73
update_gcs(AUTOTUNE_MESSAGE_STARTED);
74
break;
75
76
case TuneMode::FINISHED:
77
case TuneMode::VALIDATING:
78
// The user is now validating the tuned gains in flight
79
mode = TuneMode::VALIDATING;
80
update_gcs(AUTOTUNE_MESSAGE_TESTING);
81
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_PILOT_TESTING);
82
break;
83
}
84
85
have_position = false;
86
87
return true;
88
}
89
90
// stop - should be called when the ch7/ch8 switch is switched OFF
91
void AC_AutoTune::stop()
92
{
93
// set gains to their original values
94
load_gains(GainType::ORIGINAL);
95
96
update_gcs(AUTOTUNE_MESSAGE_STOPPED);
97
98
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_OFF);
99
100
// Note: we leave the mode as it was so that we know how the autotune ended
101
// we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch
102
}
103
104
// Autotune aux function trigger
105
void AC_AutoTune::do_aux_function(const RC_Channel::AuxSwitchPos ch_flag)
106
{
107
if (mode != TuneMode::FINISHED) {
108
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
109
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: must be complete to test gains");
110
}
111
return;
112
}
113
114
switch(ch_flag) {
115
case RC_Channel::AuxSwitchPos::LOW:
116
// load original gains
117
load_gains(GainType::ORIGINAL);
118
update_gcs(AUTOTUNE_MESSAGE_TESTING_END);
119
break;
120
case RC_Channel::AuxSwitchPos::MIDDLE:
121
// Middle position is unused for now_ms
122
break;
123
case RC_Channel::AuxSwitchPos::HIGH:
124
// Load tuned gains
125
load_gains(GainType::TUNED);
126
update_gcs(AUTOTUNE_MESSAGE_TESTING);
127
break;
128
}
129
130
testing_switch_used = true;
131
}
132
133
// Possibly save gains, called on disarm
134
void AC_AutoTune::disarmed(const bool in_autotune_mode)
135
{
136
// True if pilot is testing tuned gains
137
const bool testing_tuned = testing_switch_used && (loaded_gains == GainType::TUNED);
138
139
// True if in autotune mode and no pilot testing commands have been received
140
const bool tune_complete_no_testing = !testing_switch_used && in_autotune_mode;
141
142
if (tune_complete_no_testing || testing_tuned) {
143
save_tuning_gains();
144
} else {
145
reset();
146
}
147
}
148
149
// initialise position controller
150
bool AC_AutoTune::init_position_controller(void)
151
{
152
// initialize vertical maximum speeds and acceleration
153
init_z_limits();
154
155
// initialise the vertical position controller
156
pos_control->D_init_controller();
157
158
return true;
159
}
160
161
void AC_AutoTune::send_step_string()
162
{
163
if (pilot_override) {
164
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
165
return;
166
}
167
switch (step) {
168
case Step::WAITING_FOR_LEVEL:
169
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Leveling");
170
return;
171
case Step::UPDATE_GAINS:
172
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Updating Gains");
173
return;
174
case Step::ABORT:
175
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Aborting Test");
176
return;
177
case Step::EXECUTING_TEST:
178
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: Testing");
179
return;
180
}
181
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: unknown step");
182
}
183
184
const char *AC_AutoTune::get_tune_type_name() const
185
{
186
switch (tune_type) {
187
case TuneType::RATE_D_UP:
188
return "Rate D Up";
189
case TuneType::RATE_D_DOWN:
190
return "Rate D Down";
191
case TuneType::RATE_P_UP:
192
return "Rate P Up";
193
case TuneType::RATE_FF_UP:
194
return "Rate FF Up";
195
case TuneType::ANGLE_P_UP:
196
return "Angle P Up";
197
case TuneType::ANGLE_P_DOWN:
198
return "Angle P Down";
199
case TuneType::MAX_GAINS:
200
return "Find Max Gains";
201
case TuneType::TUNE_CHECK:
202
return "Check Tune Frequency Response";
203
case TuneType::TUNE_COMPLETE:
204
return "Tune Complete";
205
}
206
return "";
207
// this should never happen
208
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
209
}
210
211
// return current axis string
212
const char *AC_AutoTune::get_axis_name() const
213
{
214
switch (axis) {
215
case AxisType::ROLL:
216
return "Roll";
217
case AxisType::PITCH:
218
return "Pitch";
219
case AxisType::YAW:
220
return "Yaw(E)";
221
case AxisType::YAW_D:
222
return "Yaw(D)";
223
}
224
return "";
225
}
226
227
// Main update loop for Autotune mode. Handles all states: tuning, validating, or idle.
228
// Should be called at ≥100Hz for consistent performance.
229
void AC_AutoTune::run()
230
{
231
// Initialise vertical climb rate and acceleration limits
232
init_z_limits();
233
234
// Exit early if the vehicle is disarmed or motor interlock is not enabled
235
// (this condition should not occur if init() is working correctly)
236
if (!motors->armed() || !motors->get_interlock()) {
237
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
238
attitude_control->set_throttle_out(0.0f, true, 0.0f);
239
pos_control->D_relax_controller(0.0f);
240
return;
241
}
242
243
float desired_yaw_rate_rads; // used during manual control
244
get_pilot_desired_rp_yrate_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);
245
246
// Get pilot's desired climb rate
247
const float target_climb_rate_ms = get_desired_climb_rate_ms();
248
249
const bool zero_rp_input = is_zero(desired_roll_rad) && is_zero(desired_pitch_rad);
250
if (zero_rp_input) {
251
// Use position hold if enabled
252
get_poshold_attitude_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad);
253
}
254
255
const uint32_t now_ms = AP_HAL::millis();
256
257
switch (mode) {
258
case TuneMode::TUNING:
259
// Detect pilot override
260
if (!zero_rp_input || !is_zero(desired_yaw_rate_rads) || !is_zero(target_climb_rate_ms)) {
261
if (!pilot_override) {
262
pilot_override = true;
263
// Restore original gains while pilot is in control
264
}
265
// Update last override time
266
override_time = now_ms;
267
if (!zero_rp_input) {
268
// Invalidate position hold if pilot inputs roll/pitch
269
have_position = false;
270
}
271
} else if (pilot_override) {
272
// Check if pilot has released sticks long enough to resume tuning
273
if (now_ms - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) {
274
pilot_override = false;
275
step = Step::WAITING_FOR_LEVEL;
276
step_start_time_ms = now_ms;
277
level_start_time_ms = now_ms;
278
// TODO: Consider using our current target.
279
desired_yaw_rad = ahrs_view->get_yaw_rad(); // Reset yaw reference
280
}
281
}
282
283
if (pilot_override) {
284
// Pilot is actively controlling the vehicle; fly on original gains
285
if (now_ms - last_pilot_override_warning > 1000) {
286
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AutoTune: pilot overrides active");
287
last_pilot_override_warning = now_ms;
288
}
289
load_gains(GainType::ORIGINAL);
290
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);
291
} else {
292
// Autotune controls the aircraft
293
control_attitude();
294
do_gcs_announcements();
295
}
296
break;
297
298
case TuneMode::UNINITIALISED:
299
// Should never reach this state; init() must be called before run()
300
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
301
FALLTHROUGH;
302
303
case TuneMode::FAILED:
304
FALLTHROUGH;
305
306
case TuneMode::FINISHED:
307
// Tuning is complete or failed; fly using original gains
308
load_gains(GainType::ORIGINAL);
309
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);
310
break;
311
312
case TuneMode::VALIDATING:
313
// Pilot is evaluating tuned gains
314
load_gains(GainType::TUNED);
315
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rate_rads);
316
break;
317
}
318
319
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
320
321
// Update vertical position controller with pilot climb rate input
322
pos_control->D_set_pos_target_from_climb_rate_ms(target_climb_rate_ms);
323
pos_control->D_update_controller();
324
}
325
326
// return true if vehicle is close to level
327
bool AC_AutoTune::currently_level()
328
{
329
// abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS
330
const uint32_t now_ms = AP_HAL::millis();
331
if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) {
332
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually");
333
mode = TuneMode::FAILED;
334
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
335
}
336
337
// slew threshold to ensure sufficient settling time for aircraft unable to obtain small thresholds
338
// relax threshold if we pass AUTOTUNE_LEVEL_TIMEOUT_MS
339
const float threshold_mul = constrain_float((float)(now_ms - level_start_time_ms) / (float)AUTOTUNE_LEVEL_TIMEOUT_MS, 0.0, 2.0);
340
341
if (fabsf(ahrs_view->get_roll_rad() - desired_roll_rad) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {
342
return false;
343
}
344
if (fabsf(ahrs_view->get_pitch_rad() - desired_pitch_rad) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {
345
return false;
346
}
347
if (fabsf(wrap_PI(ahrs_view->get_yaw_rad() - desired_yaw_rad)) > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_ANGLE_CD)) {
348
return false;
349
}
350
if (ahrs_view->get_gyro().x > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_RP_CD)) {
351
return false;
352
}
353
if (ahrs_view->get_gyro().y > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_RP_CD)) {
354
return false;
355
}
356
if (ahrs_view->get_gyro().z > threshold_mul * cd_to_rad(AUTOTUNE_LEVEL_RATE_Y_CD)) {
357
return false;
358
}
359
return true;
360
}
361
362
// Main tuning state machine. Handles all StepTypes: WAITING_FOR_LEVEL, EXECUTING_TEST, UPDATE_GAINS, ABORT.
363
// Updates attitude controller targets and processes test results to adjust PID gains.
364
void AC_AutoTune::control_attitude()
365
{
366
rotation_rate = 0.0f;
367
lean_angle = 0.0f;
368
const float direction_sign = positive_direction ? 1.0f : -1.0f;
369
const uint32_t now_ms = AP_HAL::millis();
370
371
switch (step) {
372
373
case Step::WAITING_FOR_LEVEL: {
374
// Use intra-test gains while holding level between tests
375
load_gains(GainType::INTRA_TEST);
376
377
attitude_control->input_euler_angle_roll_pitch_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad, true);
378
379
// Require a short stable period before executing the next test
380
if (!currently_level()) {
381
step_start_time_ms = now_ms;
382
}
383
384
if (now_ms - step_start_time_ms > AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {
385
// Begin the test phase
386
step = Step::EXECUTING_TEST;
387
step_start_time_ms = now_ms;
388
step_timeout_ms = get_testing_step_timeout_ms();
389
390
// Record starting angular position and rate
391
switch (axis) {
392
case AxisType::ROLL:
393
start_rate = degrees(ahrs_view->get_gyro().x) * 100.0f;
394
start_angle = ahrs_view->roll_sensor;
395
break;
396
case AxisType::PITCH:
397
start_rate = degrees(ahrs_view->get_gyro().y) * 100.0f;
398
start_angle = ahrs_view->pitch_sensor;
399
break;
400
case AxisType::YAW:
401
case AxisType::YAW_D:
402
start_rate = degrees(ahrs_view->get_gyro().z) * 100.0f;
403
start_angle = ahrs_view->yaw_sensor;
404
break;
405
}
406
407
// Apply test gains and initialise test-specific variables
408
load_gains(GainType::TEST);
409
test_init();
410
}
411
break;
412
}
413
414
case Step::EXECUTING_TEST: {
415
// Run the test with current trial gains
416
load_gains(GainType::TEST);
417
test_run(axis, direction_sign);
418
419
// Detect failure due to reverse response or excessive lean angle
420
if (lean_angle <= -angle_lim_neg_rpy_cd() ||
421
attitude_control->lean_angle_deg() * 100 > angle_lim_max_rp_cd()) {
422
step = Step::ABORT;
423
}
424
425
#if HAL_LOGGING_ENABLED
426
Log_AutoTuneDetails();
427
attitude_control->Write_Rate(*pos_control);
428
log_pids();
429
#endif
430
431
// Update yaw target for next test if required
432
if (axis == AxisType::YAW || axis == AxisType::YAW_D) {
433
desired_yaw_rad = ahrs_view->get_yaw_rad();
434
}
435
break;
436
}
437
438
case Step::UPDATE_GAINS:
439
440
#if HAL_LOGGING_ENABLED
441
Log_AutoTune(); // Log gain adjustment results
442
#endif
443
444
// Announce test results before gains are changed
445
do_post_test_gcs_announcements();
446
447
// Update gains based on the current tuning strategy
448
switch (tune_type) {
449
case TuneType::RATE_D_UP:
450
updating_rate_d_up_all(axis);
451
break;
452
case TuneType::RATE_D_DOWN:
453
updating_rate_d_down_all(axis);
454
break;
455
case TuneType::RATE_P_UP:
456
updating_rate_p_up_all(axis);
457
break;
458
case TuneType::ANGLE_P_DOWN:
459
updating_angle_p_down_all(axis);
460
break;
461
case TuneType::ANGLE_P_UP:
462
updating_angle_p_up_all(axis);
463
break;
464
case TuneType::RATE_FF_UP:
465
updating_rate_ff_up_all(axis);
466
break;
467
case TuneType::MAX_GAINS:
468
updating_max_gains_all(axis);
469
break;
470
case TuneType::TUNE_CHECK:
471
success_counter = AUTOTUNE_SUCCESS_COUNT;
472
FALLTHROUGH;
473
case TuneType::TUNE_COMPLETE:
474
break;
475
}
476
477
// If tuning step was successful, proceed to the next step
478
if (success_counter >= AUTOTUNE_SUCCESS_COUNT) {
479
success_counter = 0;
480
step_scaler = 1.0f;
481
set_tuning_gains_with_backoff(axis);
482
next_tune_type(tune_type, false);
483
484
if (tune_type == TuneType::TUNE_COMPLETE) {
485
// Complete tuning for this axis and determine the next one
486
next_tune_type(tune_type, true);
487
report_final_gains(axis);
488
489
bool complete = false;
490
switch (axis) {
491
case AxisType::ROLL:
492
axes_completed |= AUTOTUNE_AXIS_BITMASK_ROLL;
493
if (pitch_enabled()) {
494
axis = AxisType::PITCH;
495
} else if (yaw_enabled()) {
496
axis = AxisType::YAW;
497
} else if (yaw_d_enabled()) {
498
axis = AxisType::YAW_D;
499
} else {
500
complete = true;
501
}
502
break;
503
case AxisType::PITCH:
504
axes_completed |= AUTOTUNE_AXIS_BITMASK_PITCH;
505
if (yaw_enabled()) {
506
axis = AxisType::YAW;
507
} else if (yaw_d_enabled()) {
508
axis = AxisType::YAW_D;
509
} else {
510
complete = true;
511
}
512
break;
513
case AxisType::YAW:
514
axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW;
515
if (yaw_d_enabled()) {
516
axis = AxisType::YAW_D;
517
} else {
518
complete = true;
519
}
520
break;
521
case AxisType::YAW_D:
522
axes_completed |= AUTOTUNE_AXIS_BITMASK_YAW_D;
523
complete = true;
524
break;
525
}
526
527
if (complete) {
528
mode = TuneMode::FINISHED;
529
update_gcs(AUTOTUNE_MESSAGE_SUCCESS);
530
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS);
531
AP_Notify::events.autotune_complete = true;
532
load_gains(GainType::ORIGINAL); // Reset for landing
533
} else {
534
AP_Notify::events.autotune_next_axis = true;
535
reset_update_gain_variables();
536
}
537
}
538
}
539
FALLTHROUGH;
540
541
case Step::ABORT:
542
// Recover from failed test or move on after a successful one
543
544
attitude_control->input_euler_angle_roll_pitch_yaw_rad(desired_roll_rad, desired_pitch_rad, desired_yaw_rad, true);
545
546
load_gains(GainType::INTRA_TEST);
547
548
step = Step::WAITING_FOR_LEVEL;
549
positive_direction = reverse_test_direction();
550
step_start_time_ms = now_ms;
551
level_start_time_ms = now_ms;
552
step_timeout_ms = AUTOTUNE_REQUIRED_LEVEL_TIME_MS;
553
break;
554
}
555
}
556
557
// backup_gains_and_initialise - store current gains as originals
558
// called before tuning starts to backup original gains
559
void AC_AutoTune::backup_gains_and_initialise()
560
{
561
const uint32_t now_ms = AP_HAL::millis();
562
563
// initialise state because this is our first time
564
if (roll_enabled()) {
565
axis = AxisType::ROLL;
566
} else if (pitch_enabled()) {
567
axis = AxisType::PITCH;
568
} else if (yaw_enabled()) {
569
axis = AxisType::YAW;
570
} else if (yaw_d_enabled()) {
571
axis = AxisType::YAW_D;
572
}
573
// no axes are complete
574
axes_completed = 0;
575
576
// reset update gain variables for each vehicle
577
reset_update_gain_variables();
578
579
// start at the beginning of tune sequence
580
next_tune_type(tune_type, true);
581
582
step = Step::WAITING_FOR_LEVEL;
583
positive_direction = false;
584
step_start_time_ms = now_ms;
585
level_start_time_ms = now_ms;
586
step_scaler = 1.0f;
587
588
desired_yaw_rad = ahrs_view->get_yaw_rad();
589
}
590
591
/*
592
load a specified set of gains
593
*/
594
void AC_AutoTune::load_gains(enum GainType gain_type)
595
{
596
if (loaded_gains == gain_type) {
597
// Loaded gains are already of correct type
598
return;
599
}
600
loaded_gains = gain_type;
601
602
switch (gain_type) {
603
case GainType::ORIGINAL:
604
load_orig_gains();
605
break;
606
case GainType::INTRA_TEST:
607
load_intra_test_gains();
608
break;
609
case GainType::TEST:
610
load_test_gains();
611
break;
612
case GainType::TUNED:
613
load_tuned_gains();
614
break;
615
}
616
}
617
618
// update_gcs - send message to ground station
619
void AC_AutoTune::update_gcs(uint8_t message_id) const
620
{
621
switch (message_id) {
622
case AUTOTUNE_MESSAGE_STARTED:
623
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Started");
624
break;
625
case AUTOTUNE_MESSAGE_STOPPED:
626
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"AutoTune: Stopped");
627
break;
628
case AUTOTUNE_MESSAGE_SUCCESS:
629
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Success");
630
break;
631
case AUTOTUNE_MESSAGE_FAILED:
632
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
633
break;
634
case AUTOTUNE_MESSAGE_TESTING:
635
case AUTOTUNE_MESSAGE_SAVED_GAINS:
636
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: %s gains for %s%s%s%s",
637
(message_id == AUTOTUNE_MESSAGE_SAVED_GAINS) ? "Saved" : "Pilot Testing",
638
(axes_completed&AUTOTUNE_AXIS_BITMASK_ROLL)?"Roll ":"",
639
(axes_completed&AUTOTUNE_AXIS_BITMASK_PITCH)?"Pitch ":"",
640
(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW)?"Yaw(E)":"",
641
(axes_completed&AUTOTUNE_AXIS_BITMASK_YAW_D)?"Yaw(D)":"");
642
break;
643
case AUTOTUNE_MESSAGE_TESTING_END:
644
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE,"AutoTune: original gains restored");
645
break;
646
}
647
}
648
649
// axis helper functions
650
bool AC_AutoTune::roll_enabled() const
651
{
652
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_ROLL;
653
}
654
655
bool AC_AutoTune::pitch_enabled() const
656
{
657
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_PITCH;
658
}
659
660
bool AC_AutoTune::yaw_enabled() const
661
{
662
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW;
663
}
664
665
bool AC_AutoTune::yaw_d_enabled() const
666
{
667
#if APM_BUILD_TYPE(APM_BUILD_Heli)
668
return false;
669
#else
670
return get_axis_bitmask() & AUTOTUNE_AXIS_BITMASK_YAW_D;
671
#endif
672
}
673
674
/*
675
check if we have a good position estimate
676
*/
677
bool AC_AutoTune::position_ok(void)
678
{
679
if (!AP::ahrs().have_inertial_nav()) {
680
// do not allow navigation with dcm position
681
return false;
682
}
683
684
// with EKF use filter status and ekf check
685
nav_filter_status filt_status {};
686
AP::ahrs().get_filter_status(filt_status);
687
688
// require a good absolute position and EKF must not be in const_pos_mode
689
return (filt_status.flags.horiz_pos_abs && !filt_status.flags.const_pos_mode);
690
}
691
692
// get attitude for slow position hold in autotune mode
693
void AC_AutoTune::get_poshold_attitude_rad(float &roll_out_rad, float &pitch_out_rad, float &yaw_out_rad)
694
{
695
roll_out_rad = pitch_out_rad = 0;
696
697
if (!use_poshold) {
698
// we are not trying to hold position
699
return;
700
}
701
702
// do we know where we are? If not then don't do poshold
703
if (!position_ok()) {
704
return;
705
}
706
707
if (!have_position) {
708
have_position = true;
709
start_position_ned_m = pos_control->get_pos_estimate_NED_m();
710
}
711
712
// don't go past 10 degrees, as autotune result would deteriorate too much
713
const float angle_max_rad = radians(10.0);
714
715
// hit the 10 degree limit at 20 meters position error
716
const float dist_limit_m = 20.00;
717
718
// we only start adjusting yaw if we are more than 5m from the
719
// target position. That corresponds to a lean angle of 2.5 degrees
720
const float yaw_dist_limit_m = 5.0;
721
722
Vector3f pos_error_ned_m = (pos_control->get_pos_estimate_NED_m() - start_position_ned_m).tofloat();
723
pos_error_ned_m.z = 0;
724
float dist_m = pos_error_ned_m.length();
725
if (dist_m < 0.10) {
726
// don't do anything within 10cm
727
return;
728
}
729
730
/*
731
very simple linear controller
732
*/
733
float scaling = constrain_float(angle_max_rad * dist_m / dist_limit_m, 0, angle_max_rad);
734
Vector2f angle_ne(pos_error_ned_m.x, pos_error_ned_m.y);
735
angle_ne *= scaling / dist_m;
736
737
// rotate into body frame
738
pitch_out_rad = angle_ne.x * ahrs_view->cos_yaw() + angle_ne.y * ahrs_view->sin_yaw();
739
roll_out_rad = angle_ne.x * ahrs_view->sin_yaw() - angle_ne.y * ahrs_view->cos_yaw();
740
741
if (dist_m < yaw_dist_limit_m) {
742
// no yaw adjustment
743
return;
744
}
745
746
/*
747
also point so that test occurs perpendicular to the wind,
748
if we have drifted more than yaw_dist_limit_m from the desired
749
position. This ensures that autotune doesn't have to deal with
750
more than 2.5 degrees of attitude on the axis it is tuning
751
*/
752
float target_yaw_rad = atan2f(pos_error_ned_m.y, pos_error_ned_m.x);
753
if (axis == AxisType::PITCH) {
754
// for roll and yaw tuning we point along the wind, for pitch
755
// we point across the wind
756
target_yaw_rad += radians(90);
757
}
758
// go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation
759
if (fabsf(yaw_out_rad - target_yaw_rad) > radians(95.0)) {
760
target_yaw_rad += radians(180.0);
761
}
762
763
yaw_out_rad = target_yaw_rad;
764
}
765
766
// get the next tune type
767
void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset)
768
{
769
if (reset) {
770
set_tune_sequence();
771
tune_seq_index = 0;
772
} else if (curr_tune_type == TuneType::TUNE_COMPLETE) {
773
// leave tune_type as TUNE_COMPLETE to initiate next axis or exit autotune
774
return;
775
} else {
776
tune_seq_index++;
777
}
778
779
curr_tune_type = tune_seq[tune_seq_index];
780
}
781
782
#endif // AC_AUTOTUNE_ENABLED
783
784