APM:Copter
mode_autotune.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if AUTOTUNE_ENABLED == ENABLED
4 
5 /*
6  * Init and run calls for autotune flight mode
7  *
8  * Instructions:
9  * 1) Set up one flight mode switch position to be AltHold.
10  * 2) Set the Ch7 Opt or Ch8 Opt to AutoTune to allow you to turn the auto tuning on/off with the ch7 or ch8 switch.
11  * 3) Ensure the ch7 or ch8 switch is in the LOW position.
12  * 4) Wait for a calm day and go to a large open area.
13  * 5) Take off and put the vehicle into AltHold mode at a comfortable altitude.
14  * 6) Set the ch7/ch8 switch to the HIGH position to engage auto tuning:
15  * a) You will see it twitch about 20 degrees left and right for a few minutes, then it will repeat forward and back.
16  * b) Use the roll and pitch stick at any time to reposition the copter if it drifts away (it will use the original PID gains during repositioning and between tests).
17  * When you release the sticks it will continue auto tuning where it left off.
18  * c) Move the ch7/ch8 switch into the LOW position at any time to abandon the autotuning and return to the origin PIDs.
19  * d) Make sure that you do not have any trim set on your transmitter or the autotune may not get the signal that the sticks are centered.
20  * 7) When the tune completes the vehicle will change back to the original PID gains.
21  * 8) Put the ch7/ch8 switch into the LOW position then back to the HIGH position to test the tuned PID gains.
22  * 9) Put the ch7/ch8 switch into the LOW position to fly using the original PID gains.
23  * 10) If you are happy with the autotuned PID gains, leave the ch7/ch8 switch in the HIGH position, land and disarm to save the PIDs permanently.
24  * If you DO NOT like the new PIDS, switch ch7/ch8 LOW to return to the original PIDs. The gains will not be saved when you disarm
25  *
26  * What it's doing during each "twitch":
27  * a) invokes 90 deg/sec rate request
28  * b) records maximum "forward" roll rate and bounce back rate
29  * c) when copter reaches 20 degrees or 1 second has passed, it commands level
30  * d) tries to keep max rotation rate between 80% ~ 100% of requested rate (90deg/sec) by adjusting rate P
31  * e) increases rate D until the bounce back becomes greater than 10% of requested rate (90deg/sec)
32  * f) decreases rate D until the bounce back becomes less than 10% of requested rate (90deg/sec)
33  * g) increases rate P until the max rotate rate becomes greater than the request rate (90deg/sec)
34  * h) invokes a 20deg angle request on roll or pitch
35  * i) increases stab P until the maximum angle becomes greater than 110% of the requested angle (20deg)
36  * j) decreases stab P by 25%
37  *
38  */
39 
40 #define AUTOTUNE_AXIS_BITMASK_ROLL 1
41 #define AUTOTUNE_AXIS_BITMASK_PITCH 2
42 #define AUTOTUNE_AXIS_BITMASK_YAW 4
43 
44 #define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds
45 #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000 // timeout for tuning mode's testing step
46 #define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level
47 #define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch
48 #define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw
49 #define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 500 // time we require the copter to be level
50 #define AUTOTUNE_RD_STEP 0.05f // minimum increment when increasing/decreasing Rate D term
51 #define AUTOTUNE_RP_STEP 0.05f // minimum increment when increasing/decreasing Rate P term
52 #define AUTOTUNE_SP_STEP 0.05f // minimum increment when increasing/decreasing Stab P term
53 #define AUTOTUNE_PI_RATIO_FOR_TESTING 0.1f // I is set 10x smaller than P during testing
54 #define AUTOTUNE_PI_RATIO_FINAL 1.0f // I is set 1x P after testing
55 #define AUTOTUNE_YAW_PI_RATIO_FINAL 0.1f // I is set 1x P after testing
56 #define AUTOTUNE_RD_MAX 0.200f // maximum Rate D value
57 #define AUTOTUNE_RLPF_MIN 1.0f // minimum Rate Yaw filter value
58 #define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value
59 #define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value
60 #define AUTOTUNE_RP_MAX 2.0f // maximum Rate P value
61 #define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value
62 #define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value
63 #define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch
64 #define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw
65 #define AUTOTUNE_Y_FILT_FREQ 10.0f // Autotune filter frequency when testing Yaw
66 #define AUTOTUNE_SUCCESS_COUNT 4 // The number of successful iterations we need to freeze at current gains
67 #define AUTOTUNE_D_UP_DOWN_MARGIN 0.2f // The margin below the target that we tune D in
68 #define AUTOTUNE_RD_BACKOFF 1.0f // Rate D gains are reduced to 50% of their maximum value discovered during tuning
69 #define AUTOTUNE_RP_BACKOFF 1.0f // Rate P gains are reduced to 97.5% of their maximum value discovered during tuning
70 #define AUTOTUNE_SP_BACKOFF 0.9f // Stab P gains are reduced to 90% of their maximum value discovered during tuning
71 #define AUTOTUNE_ACCEL_RP_BACKOFF 1.0f // back off from maximum acceleration
72 #define AUTOTUNE_ACCEL_Y_BACKOFF 1.0f // back off from maximum acceleration
73 
74 // roll and pitch axes
75 #define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD 2000 // target angle during TESTING_RATE step that will cause us to move to next step
76 #define AUTOTUNE_TARGET_RATE_RLLPIT_CDS 18000 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
77 #define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD 1000 // minimum target angle during TESTING_RATE step that will cause us to move to next step
78 #define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS 4500 // target roll/pitch rate during AUTOTUNE_STEP_TWITCHING step
79 
80 // yaw axis
81 #define AUTOTUNE_TARGET_ANGLE_YAW_CD 3000 // target angle during TESTING_RATE step that will cause us to move to next step
82 #define AUTOTUNE_TARGET_RATE_YAW_CDS 9000 // target yaw rate during AUTOTUNE_STEP_TWITCHING step
83 #define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD 500 // minimum target angle during TESTING_RATE step that will cause us to move to next step
84 #define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS 1500 // minimum target yaw rate during AUTOTUNE_STEP_TWITCHING step
85 
86 // Auto Tune message ids for ground station
87 #define AUTOTUNE_MESSAGE_STARTED 0
88 #define AUTOTUNE_MESSAGE_STOPPED 1
89 #define AUTOTUNE_MESSAGE_SUCCESS 2
90 #define AUTOTUNE_MESSAGE_FAILED 3
91 #define AUTOTUNE_MESSAGE_SAVED_GAINS 4
92 
93 #define AUTOTUNE_ANNOUNCE_INTERVAL_MS 2000
94 
95 // autotune_init - should be called when autotune mode is selected
96 bool Copter::ModeAutoTune::init(bool ignore_checks)
97 {
98  bool success = true;
99 
100  switch (mode) {
101  case FAILED:
102  // autotune has been run but failed so reset state to uninitialized
104  // fall through to restart the tuning
105  FALLTHROUGH;
106 
107  case UNINITIALISED:
108  // autotune has never been run
109  success = start(false);
110  if (success) {
111  // so store current gains as original gains
113  // advance mode to tuning
114  mode = TUNING;
115  // send message to ground station that we've started tuning
117  }
118  break;
119 
120  case TUNING:
121  // we are restarting tuning after the user must have switched ch7/ch8 off so we restart tuning where we left off
122  success = start(false);
123  if (success) {
124  // reset gains to tuning-start gains (i.e. low I term)
126  // write dataflash log even and send message to ground station
129  }
130  break;
131 
132  case SUCCESS:
133  // we have completed a tune and the pilot wishes to test the new gains in the current flight mode
134  // so simply apply tuning gains (i.e. do not change flight mode)
137  break;
138  }
139 
140  // only do position hold if starting autotune from LOITER or POSHOLD
141  use_poshold = (copter.control_mode == LOITER || copter.control_mode == POSHOLD);
142  have_position = false;
143 
144  return success;
145 }
146 
147 // stop - should be called when the ch7/ch8 switch is switched OFF
149 {
150  // set gains to their original values
151  load_orig_gains();
152 
153  // re-enable angle-to-rate request limits
154  attitude_control->use_sqrt_controller(true);
155 
156  // log off event and send message to ground station
159 
160  // Note: we leave the mode as it was so that we know how the autotune ended
161  // we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch
162 }
163 
164 // start - Initialize autotune flight mode
165 bool Copter::ModeAutoTune::start(bool ignore_checks)
166 {
167  // only allow flip from Stabilize, AltHold, PosHold or Loiter modes
168  if (copter.control_mode != STABILIZE && copter.control_mode != ALT_HOLD &&
169  copter.control_mode != LOITER && copter.control_mode != POSHOLD) {
170  return false;
171  }
172 
173  // ensure throttle is above zero
174  if (ap.throttle_zero) {
175  return false;
176  }
177 
178  // ensure we are flying
179  if (!motors->armed() || !ap.auto_armed || ap.land_complete) {
180  return false;
181  }
182 
183  // initialize vertical speeds and leash lengths
186 
187  // initialise position and desired velocity
188  if (!pos_control->is_active_z()) {
191  }
192 
193  return true;
194 }
195 
197 {
198  switch (level_problem.issue) {
199  case LEVEL_ISSUE_NONE:
200  return "None";
202  return "Angle(R)";
204  return "Angle(P)";
206  return "Angle(Y)";
208  return "Rate(R)";
210  return "Rate(P)";
212  return "Rate(Y)";
213  }
214  return "Bug";
215 }
216 
218 {
219  if (pilot_override) {
220  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
221  return;
222  }
223  switch (step) {
224  case WAITING_FOR_LEVEL:
225  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: WFL (%s) (%f > %f)", level_issue_string(), (double)(level_problem.current*0.01f), (double)(level_problem.maximum*0.01f));
226  return;
227  case UPDATE_GAINS:
228  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: UPDATING_GAINS");
229  return;
230  case TWITCHING:
231  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: TWITCHING");
232  return;
233  }
234  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: unknown step");
235 }
236 
238 {
239  switch (tune_type) {
240  case RD_UP:
241  return "Rate D Up";
242  case RD_DOWN:
243  return "Rate D Down";
244  case RP_UP:
245  return "Rate P Up";
246  case SP_DOWN:
247  return "Angle P Down";
248  case SP_UP:
249  return "Angle P Up";
250  }
251  return "Bug";
252 }
253 
255 {
256  const uint32_t now = millis();
258  return;
259  }
260  float tune_rp = 0.0f;
261  float tune_rd = 0.0f;
262  float tune_sp = 0.0f;
263  float tune_accel = 0.0f;
264  char axis_char = '?';
265  switch (axis) {
266  case ROLL:
267  tune_rp = tune_roll_rp;
268  tune_rd = tune_roll_rd;
269  tune_sp = tune_roll_sp;
270  tune_accel = tune_roll_accel;
271  axis_char = 'R';
272  break;
273  case PITCH:
274  tune_rp = tune_pitch_rp;
275  tune_rd = tune_pitch_rd;
276  tune_sp = tune_pitch_sp;
277  tune_accel = tune_pitch_accel;
278  axis_char = 'P';
279  break;
280  case YAW:
281  tune_rp = tune_yaw_rp;
282  tune_rd = tune_yaw_rLPF;
283  tune_sp = tune_yaw_sp;
284  tune_accel = tune_yaw_accel;
285  axis_char = 'Y';
286  break;
287  }
288 
289  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis_char, type_string());
291  if (!is_zero(lean_angle)) {
292  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: lean=%f target=%f", (double)lean_angle, (double)target_angle);
293  }
294  if (!is_zero(rotation_rate)) {
295  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rotation=%f target=%f", (double)(rotation_rate*0.01f), (double)(target_rate*0.01f));
296  }
297  switch (tune_type) {
298  case RD_UP:
299  case RD_DOWN:
300  case RP_UP:
301  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f d=%f", (double)tune_rp, (double)tune_rd);
302  break;
303  case SP_DOWN:
304  case SP_UP:
305  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f accel=%f", (double)tune_sp, (double)tune_accel);
306  break;
307  }
308  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: success %u/%u", counter, AUTOTUNE_SUCCESS_COUNT);
309 
310  announce_time = now;
311 }
312 
313 // run - runs the autotune flight mode
314 // should be called at 100hz or more
316 {
317  float target_roll, target_pitch;
318  float target_yaw_rate;
319  int16_t target_climb_rate;
320 
321  // initialize vertical speeds and acceleration
324 
325  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
326  // this should not actually be possible because of the init() checks
327  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
330  return;
331  }
332 
333  // apply SIMPLE mode transform to pilot inputs
335 
336  // get pilot desired lean angles
337  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max());
338 
339  // get pilot's desired yaw rate
341 
342  // get pilot desired climb rate
344 
345  // get avoidance adjusted climb rate
346  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
347 
348  // check for pilot requested take-off - this should not actually be possible because of init() checks
349  if (ap.land_complete && target_climb_rate > 0) {
350  // indicate we are taking off
351  set_land_complete(false);
352  // clear i term when we're taking off
354  }
355 
356  // reset target lean angles and heading while landed
357  if (ap.land_complete) {
358  // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
359  if (target_climb_rate < 0.0f) {
360  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
361  } else {
362  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
363  }
364  attitude_control->reset_rate_controller_I_terms();
365  attitude_control->set_yaw_target_to_current_heading();
366  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
369  }else{
370  // check if pilot is overriding the controls
371  bool zero_rp_input = is_zero(target_roll) && is_zero(target_pitch);
372  if (!zero_rp_input || !is_zero(target_yaw_rate) || target_climb_rate != 0) {
373  if (!pilot_override) {
374  pilot_override = true;
375  // set gains to their original values
376  load_orig_gains();
377  attitude_control->use_sqrt_controller(true);
378  }
379  // reset pilot override time
380  override_time = millis();
381  if (!zero_rp_input) {
382  // only reset position on roll or pitch input
383  have_position = false;
384  }
385  }else if (pilot_override) {
386  // check if we should resume tuning after pilot's override
388  pilot_override = false; // turn off pilot override
389  // set gains to their intra-test values (which are very close to the original gains)
390  // load_intra_test_gains(); //I think we should be keeping the originals here to let the I term settle quickly
391  step = WAITING_FOR_LEVEL; // set tuning step back from beginning
393  }
394  }
395 
396  if (zero_rp_input) {
397  // pilot input on throttle and yaw will still use position hold if enabled
398  get_poshold_attitude(target_roll, target_pitch, desired_yaw);
399  }
400 
401  // set motors to full range
402  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
403 
404  // if pilot override call attitude controller
405  if (pilot_override || mode != TUNING) {
406  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
407  }else{
408  // somehow get attitude requests from autotuning
410  // tell the user what's going on
412  }
413 
414  // call position controller
415  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
417  }
418 }
419 
421 {
422  if (current > maximum) {
423  level_problem.current = current;
424  level_problem.maximum = maximum;
425  level_problem.issue = issue;
426  return false;
427  }
428  return true;
429 }
430 
432 {
434  labs(ahrs.roll_sensor - roll_cd),
436  return false;
437  }
438 
440  labs(ahrs.pitch_sensor - pitch_cd),
442  return false;
443  }
445  labs(wrap_180_cd(ahrs.yaw_sensor-(int32_t)desired_yaw)),
447  return false;
448  }
450  (ToDeg(ahrs.get_gyro().x) * 100.0f),
452  return false;
453  }
455  (ToDeg(ahrs.get_gyro().y) * 100.0f),
457  return false;
458  }
460  (ToDeg(ahrs.get_gyro().z) * 100.0f),
462  return false;
463  }
464  return true;
465 }
466 
467 // attitude_controller - sets attitude control targets during tuning
469 {
470  rotation_rate = 0.0f; // rotation rate in radians/second
471  lean_angle = 0.0f;
472  const float direction_sign = positive_direction ? 1.0f : -1.0f;
473 
474  // check tuning step
475  switch (step) {
476 
477  case WAITING_FOR_LEVEL:
478  // Note: we should be using intra-test gains (which are very close to the original gains but have lower I)
479  // re-enable rate limits
480  attitude_control->use_sqrt_controller(true);
481 
483 
484  // hold level attitude
485  attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw, true);
486 
487  // hold the copter level for 0.5 seconds before we begin a twitch
488  // reset counter if we are no longer level
489  if (!currently_level()) {
491  }
492 
493  // if we have been level for a sufficient amount of time (0.5 seconds) move onto tuning step
495  gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Twitch");
496  // initiate variables for next step
497  step = TWITCHING;
500  twitch_first_iter = true;
501  test_rate_max = 0.0f;
502  test_rate_min = 0.0f;
503  test_angle_max = 0.0f;
504  test_angle_min = 0.0f;
506  rate_max = 0.0f;
507  // set gains to their to-be-tested values
509  }
510 
511  switch (axis) {
512  case ROLL:
515  start_rate = ToDeg(ahrs.get_gyro().x) * 100.0f;
517  rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_roll_pid().filt_hz()*2.0f);
518  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
520  } else {
522  }
523  break;
524  case PITCH:
527  start_rate = ToDeg(ahrs.get_gyro().y) * 100.0f;
528  start_angle = ahrs.pitch_sensor;
529  rotation_rate_filt.set_cutoff_frequency(attitude_control->get_rate_pitch_pid().filt_hz()*2.0f);
530  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
532  } else {
534  }
535  break;
536  case YAW:
539  start_rate = ToDeg(ahrs.get_gyro().z) * 100.0f;
540  start_angle = ahrs.yaw_sensor;
542  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
544  } else {
546  }
547  break;
548  }
549  break;
550 
551  case TWITCHING:
552  // Run the twitching step
553  // Note: we should be using intra-test gains (which are very close to the original gains but have lower I)
554 
555  // disable rate limits
556  attitude_control->use_sqrt_controller(false);
557  // hold current attitude
558  attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f);
559 
560  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
561  // step angle targets on first iteration
562  if (twitch_first_iter) {
563  twitch_first_iter = false;
564  // Testing increasing stabilize P gain so will set lean angle target
565  switch (axis) {
566  case ROLL:
567  // request roll to 20deg
568  attitude_control->input_angle_step_bf_roll_pitch_yaw(direction_sign * target_angle, 0.0f, 0.0f);
569  break;
570  case PITCH:
571  // request pitch to 20deg
572  attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, direction_sign * target_angle, 0.0f);
573  break;
574  case YAW:
575  // request pitch to 20deg
576  attitude_control->input_angle_step_bf_roll_pitch_yaw(0.0f, 0.0f, direction_sign * target_angle);
577  break;
578  }
579  }
580  } else {
581  // Testing rate P and D gains so will set body-frame rate targets.
582  // Rate controller will use existing body-frame rates and convert to motor outputs
583  // for all axes except the one we override here.
584  switch (axis) {
585  case ROLL:
586  // override body-frame roll rate
587  attitude_control->rate_bf_roll_target(direction_sign * target_rate + start_rate);
588  break;
589  case PITCH:
590  // override body-frame pitch rate
591  attitude_control->rate_bf_pitch_target(direction_sign * target_rate + start_rate);
592  break;
593  case YAW:
594  // override body-frame yaw rate
595  attitude_control->rate_bf_yaw_target(direction_sign * target_rate + start_rate);
596  break;
597  }
598  }
599 
600  // capture this iterations rotation rate and lean angle
601  // Add filter to measurements
602  switch (axis) {
603  case ROLL:
604  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
605  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().x) * 100.0f), copter.scheduler.get_loop_period_s());
606  } else {
607  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().x) * 100.0f - start_rate), copter.scheduler.get_loop_period_s());
608  }
609  lean_angle = direction_sign * (ahrs.roll_sensor - (int32_t)start_angle);
610  break;
611  case PITCH:
612  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
613  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().y) * 100.0f), copter.scheduler.get_loop_period_s());
614  } else {
615  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().y) * 100.0f - start_rate), copter.scheduler.get_loop_period_s());
616  }
617  lean_angle = direction_sign * (ahrs.pitch_sensor - (int32_t)start_angle);
618  break;
619  case YAW:
620  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
621  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().z) * 100.0f), copter.scheduler.get_loop_period_s());
622  } else {
623  rotation_rate = rotation_rate_filt.apply(direction_sign * (ToDeg(ahrs.get_gyro().z) * 100.0f - start_rate), copter.scheduler.get_loop_period_s());
624  }
625  lean_angle = direction_sign * wrap_180_cd(ahrs.yaw_sensor-(int32_t)start_angle);
626  break;
627  }
628 
629  switch (tune_type) {
630  case RD_UP:
631  case RD_DOWN:
634  if (lean_angle >= target_angle) {
635  step = UPDATE_GAINS;
636  }
637  break;
638  case RP_UP:
641  if (lean_angle >= target_angle) {
642  step = UPDATE_GAINS;
643  }
644  break;
645  case SP_DOWN:
646  case SP_UP:
649  break;
650  }
651 
652  // log this iterations lean angle and rotation rate
653 #if LOGGING_ENABLED == ENABLED
655  copter.DataFlash.Log_Write_Rate(ahrs, *motors, *attitude_control, *pos_control);
656 #endif
657  break;
658 
659  case UPDATE_GAINS:
660 
661  // re-enable rate limits
662  attitude_control->use_sqrt_controller(true);
663 
664 #if LOGGING_ENABLED == ENABLED
665  // log the latest gains
666  if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
667  switch (axis) {
668  case ROLL:
670  break;
671  case PITCH:
673  break;
674  case YAW:
676  break;
677  }
678  } else {
679  switch (axis) {
680  case ROLL:
682  break;
683  case PITCH:
685  break;
686  case YAW:
688  break;
689  }
690  }
691 #endif
692 
693  // Check results after mini-step to increase rate D gain
694  switch (tune_type) {
695  case RD_UP:
696  switch (axis) {
697  case ROLL:
699  break;
700  case PITCH:
702  break;
703  case YAW:
705  break;
706  }
707  break;
708  // Check results after mini-step to decrease rate D gain
709  case RD_DOWN:
710  switch (axis) {
711  case ROLL:
713  break;
714  case PITCH:
716  break;
717  case YAW:
719  break;
720  }
721  break;
722  // Check results after mini-step to increase rate P gain
723  case RP_UP:
724  switch (axis) {
725  case ROLL:
727  break;
728  case PITCH:
730  break;
731  case YAW:
733  break;
734  }
735  break;
736  // Check results after mini-step to increase stabilize P gain
737  case SP_DOWN:
738  switch (axis) {
739  case ROLL:
741  break;
742  case PITCH:
744  break;
745  case YAW:
747  break;
748  }
749  break;
750  // Check results after mini-step to increase stabilize P gain
751  case SP_UP:
752  switch (axis) {
753  case ROLL:
755  break;
756  case PITCH:
758  break;
759  case YAW:
761  break;
762  }
763  break;
764  }
765 
766  // we've complete this step, finalize pids and move to next step
768 
769  // reset counter
770  counter = 0;
771 
772  // move to the next tuning type
773  switch (tune_type) {
774  case RD_UP:
776  break;
777  case RD_DOWN:
779  switch (axis) {
780  case ROLL:
782  tune_roll_rp = MAX(AUTOTUNE_RP_MIN, tune_roll_rp * AUTOTUNE_RD_BACKOFF);
783  break;
784  case PITCH:
785  tune_pitch_rd = MAX(g.autotune_min_d, tune_pitch_rd * AUTOTUNE_RD_BACKOFF);
786  tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RD_BACKOFF);
787  break;
788  case YAW:
789  tune_yaw_rLPF = MAX(AUTOTUNE_RLPF_MIN, tune_yaw_rLPF * AUTOTUNE_RD_BACKOFF);
790  tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RD_BACKOFF);
791  break;
792  }
793  break;
794  case RP_UP:
796  switch (axis) {
797  case ROLL:
799  break;
800  case PITCH:
801  tune_pitch_rp = MAX(AUTOTUNE_RP_MIN, tune_pitch_rp * AUTOTUNE_RP_BACKOFF);
802  break;
803  case YAW:
804  tune_yaw_rp = MAX(AUTOTUNE_RP_MIN, tune_yaw_rp * AUTOTUNE_RP_BACKOFF);
805  break;
806  }
807  break;
808  case SP_DOWN:
810  break;
811  case SP_UP:
812  // we've reached the end of a D-up-down PI-up-down tune type cycle
813  tune_type = RD_UP;
814 
815  // advance to the next axis
816  bool complete = false;
817  switch (axis) {
818  case ROLL:
821  if (pitch_enabled()) {
822  axis = PITCH;
823  } else if (yaw_enabled()) {
824  axis = YAW;
825  } else {
826  complete = true;
827  }
828  break;
829  case PITCH:
830  tune_pitch_sp = MAX(AUTOTUNE_SP_MIN, tune_pitch_sp * AUTOTUNE_SP_BACKOFF);
831  tune_pitch_accel = MAX(AUTOTUNE_RP_ACCEL_MIN, test_accel_max * AUTOTUNE_ACCEL_RP_BACKOFF);
832  if (yaw_enabled()) {
833  axis = YAW;
834  } else {
835  complete = true;
836  }
837  break;
838  case YAW:
839  tune_yaw_sp = MAX(AUTOTUNE_SP_MIN, tune_yaw_sp * AUTOTUNE_SP_BACKOFF);
841  complete = true;
842  break;
843  }
844 
845  // if we've just completed all axes we have successfully completed the autotune
846  // change to TESTING mode to allow user to fly with new gains
847  if (complete) {
848  mode = SUCCESS;
852  } else {
854  }
855  break;
856  }
857  }
858 
859  // reverse direction
861 
862  if (axis == YAW) {
863  attitude_control->input_euler_angle_roll_pitch_yaw(0.0f, 0.0f, ahrs.yaw_sensor, false);
864  }
865 
866  // set gains to their intra-test values (which are very close to the original gains)
868 
869  // reset testing step
872  break;
873  }
874 }
875 
876 // backup_gains_and_initialise - store current gains as originals
877 // called before tuning starts to backup original gains
879 {
880  // initialise state because this is our first time
881  if (roll_enabled()) {
882  axis = ROLL;
883  } else if (pitch_enabled()) {
884  axis = PITCH;
885  } else if (yaw_enabled()) {
886  axis = YAW;
887  }
888  positive_direction = false;
891  tune_type = RD_UP;
892 
894 
896 
897  orig_bf_feedforward = attitude_control->get_bf_feedforward();
898 
899  // backup original pids and initialise tuned pid values
900  orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
901  orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
902  orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
903  orig_roll_sp = attitude_control->get_angle_roll_p().kP();
904  orig_roll_accel = attitude_control->get_accel_roll_max();
905  tune_roll_rp = attitude_control->get_rate_roll_pid().kP();
906  tune_roll_rd = attitude_control->get_rate_roll_pid().kD();
907  tune_roll_sp = attitude_control->get_angle_roll_p().kP();
908  tune_roll_accel = attitude_control->get_accel_roll_max();
909 
910  orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
911  orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
912  orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
913  orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
914  orig_pitch_accel = attitude_control->get_accel_pitch_max();
915  tune_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
916  tune_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
917  tune_pitch_sp = attitude_control->get_angle_pitch_p().kP();
918  tune_pitch_accel = attitude_control->get_accel_pitch_max();
919 
920  orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
921  orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
922  orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
923  orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_hz();
924  orig_yaw_accel = attitude_control->get_accel_yaw_max();
925  orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
926  tune_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
927  tune_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_hz();
928  tune_yaw_sp = attitude_control->get_angle_yaw_p().kP();
929  tune_yaw_accel = attitude_control->get_accel_yaw_max();
930 
932 }
933 
934 // load_orig_gains - set gains to their original values
935 // called by stop and failed functions
937 {
938  attitude_control->bf_feedforward(orig_bf_feedforward);
939  if (roll_enabled()) {
940  if (!is_zero(orig_roll_rp)) {
941  attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
942  attitude_control->get_rate_roll_pid().kI(orig_roll_ri);
943  attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
944  attitude_control->get_angle_roll_p().kP(orig_roll_sp);
945  attitude_control->set_accel_roll_max(orig_roll_accel);
946  }
947  }
948  if (pitch_enabled()) {
949  if (!is_zero(orig_pitch_rp)) {
950  attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
951  attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri);
952  attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
953  attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
954  attitude_control->set_accel_pitch_max(orig_pitch_accel);
955  }
956  }
957  if (yaw_enabled()) {
958  if (!is_zero(orig_yaw_rp)) {
959  attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
960  attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri);
961  attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
962  attitude_control->get_rate_yaw_pid().filt_hz(orig_yaw_rLPF);
963  attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
964  attitude_control->set_accel_yaw_max(orig_yaw_accel);
965  }
966  }
967 }
968 
969 // load_tuned_gains - load tuned gains
971 {
972  if (!attitude_control->get_bf_feedforward()) {
973  attitude_control->bf_feedforward(true);
974  attitude_control->set_accel_roll_max(0.0f);
975  attitude_control->set_accel_pitch_max(0.0f);
976  }
977  if (roll_enabled()) {
978  if (!is_zero(tune_roll_rp)) {
979  attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
980  attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
981  attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
982  attitude_control->get_angle_roll_p().kP(tune_roll_sp);
983  attitude_control->set_accel_roll_max(tune_roll_accel);
984  }
985  }
986  if (pitch_enabled()) {
987  if (!is_zero(tune_pitch_rp)) {
988  attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
989  attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
990  attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
991  attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
992  attitude_control->set_accel_pitch_max(tune_pitch_accel);
993  }
994  }
995  if (yaw_enabled()) {
996  if (!is_zero(tune_yaw_rp)) {
997  attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
999  attitude_control->get_rate_yaw_pid().kD(0.0f);
1000  attitude_control->get_rate_yaw_pid().filt_hz(tune_yaw_rLPF);
1001  attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
1002  attitude_control->set_accel_yaw_max(tune_yaw_accel);
1003  }
1004  }
1005 }
1006 
1007 // load_intra_test_gains - gains used between tests
1008 // called during testing mode's update-gains step to set gains ahead of return-to-level step
1010 {
1011  // we are restarting tuning so reset gains to tuning-start gains (i.e. low I term)
1012  // sanity check the gains
1013  attitude_control->bf_feedforward(true);
1014  if (roll_enabled()) {
1015  attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
1017  attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
1018  attitude_control->get_angle_roll_p().kP(orig_roll_sp);
1019  }
1020  if (pitch_enabled()) {
1021  attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
1023  attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
1024  attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
1025  }
1026  if (yaw_enabled()) {
1027  attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
1029  attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
1030  attitude_control->get_rate_yaw_pid().filt_hz(orig_yaw_rLPF);
1031  attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
1032  }
1033 }
1034 
1035 // load_twitch_gains - load the to-be-tested gains for a single axis
1036 // called by attitude_control() just before it beings testing a gain (i.e. just before it twitches)
1038 {
1039  switch (axis) {
1040  case ROLL:
1041  attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
1042  attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f);
1043  attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
1044  attitude_control->get_angle_roll_p().kP(tune_roll_sp);
1045  break;
1046  case PITCH:
1047  attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
1048  attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f);
1049  attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
1050  attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
1051  break;
1052  case YAW:
1053  attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
1054  attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f);
1055  attitude_control->get_rate_yaw_pid().kD(0.0f);
1056  attitude_control->get_rate_yaw_pid().filt_hz(tune_yaw_rLPF);
1057  attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
1058  break;
1059  }
1060 }
1061 
1062 // save_tuning_gains - save the final tuned gains for each axis
1063 // save discovered gains to eeprom if autotuner is enabled (i.e. switch is in the high position)
1065 {
1066  // if we successfully completed tuning
1067  if (mode == SUCCESS) {
1068 
1069  if (!attitude_control->get_bf_feedforward()) {
1070  attitude_control->bf_feedforward_save(true);
1071  attitude_control->save_accel_roll_max(0.0f);
1072  attitude_control->save_accel_pitch_max(0.0f);
1073  }
1074 
1075  // sanity check the rate P values
1076  if (roll_enabled() && !is_zero(tune_roll_rp)) {
1077  // rate roll gains
1078  attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
1079  attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
1080  attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
1081  attitude_control->get_rate_roll_pid().save_gains();
1082 
1083  // stabilize roll
1084  attitude_control->get_angle_roll_p().kP(tune_roll_sp);
1085  attitude_control->get_angle_roll_p().save_gains();
1086 
1087  // acceleration roll
1088  attitude_control->save_accel_roll_max(tune_roll_accel);
1089 
1090  // resave pids to originals in case the autotune is run again
1091  orig_roll_rp = attitude_control->get_rate_roll_pid().kP();
1092  orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
1093  orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
1094  orig_roll_sp = attitude_control->get_angle_roll_p().kP();
1095  orig_roll_accel = attitude_control->get_accel_roll_max();
1096  }
1097 
1098  if (pitch_enabled() && !is_zero(tune_pitch_rp)) {
1099  // rate pitch gains
1100  attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
1101  attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
1102  attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
1103  attitude_control->get_rate_pitch_pid().save_gains();
1104 
1105  // stabilize pitch
1106  attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
1107  attitude_control->get_angle_pitch_p().save_gains();
1108 
1109  // acceleration pitch
1110  attitude_control->save_accel_pitch_max(tune_pitch_accel);
1111 
1112  // resave pids to originals in case the autotune is run again
1113  orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP();
1114  orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
1115  orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
1116  orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
1117  orig_pitch_accel = attitude_control->get_accel_pitch_max();
1118  }
1119 
1120  if (yaw_enabled() && !is_zero(tune_yaw_rp)) {
1121  // rate yaw gains
1122  attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
1124  attitude_control->get_rate_yaw_pid().kD(0.0f);
1125  attitude_control->get_rate_yaw_pid().filt_hz(tune_yaw_rLPF);
1126  attitude_control->get_rate_yaw_pid().save_gains();
1127 
1128  // stabilize yaw
1129  attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
1130  attitude_control->get_angle_yaw_p().save_gains();
1131 
1132  // acceleration yaw
1133  attitude_control->save_accel_yaw_max(tune_yaw_accel);
1134 
1135  // resave pids to originals in case the autotune is run again
1136  orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP();
1137  orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
1138  orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
1139  orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_hz();
1140  orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
1141  orig_yaw_accel = attitude_control->get_accel_pitch_max();
1142  }
1143  // update GCS and log save gains event
1146  // reset Autotune so that gains are not saved again and autotune can be run again.
1147  mode = UNINITIALISED;
1148  }
1149 }
1150 
1151 // update_gcs - send message to ground station
1152 void Copter::ModeAutoTune::update_gcs(uint8_t message_id)
1153 {
1154  switch (message_id) {
1156  gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Started");
1157  break;
1159  gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Stopped");
1160  break;
1162  gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Success");
1163  break;
1165  gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
1166  break;
1168  gcs().send_text(MAV_SEVERITY_INFO,"AutoTune: Saved gains");
1169  break;
1170  }
1171 }
1172 
1173 // axis helper functions
1176 }
1177 
1180 }
1181 
1184 }
1185 
1186 // twitching_test_rate - twitching tests
1187 // update min and max and test for end conditions
1188 void Copter::ModeAutoTune::twitching_test_rate(float rate, float rate_target_max, float &meas_rate_min, float &meas_rate_max)
1189 {
1190  // capture maximum rate
1191  if (rate > meas_rate_max) {
1192  // the measurement is continuing to increase without stopping
1193  meas_rate_max = rate;
1194  meas_rate_min = rate;
1195  }
1196 
1197  // capture minimum measurement after the measurement has peaked (aka "bounce back")
1198  if ((rate < meas_rate_min) && (meas_rate_max > rate_target_max * 0.5f)) {
1199  // the measurement is bouncing back
1200  meas_rate_min = rate;
1201  }
1202 
1203  // calculate early stopping time based on the time it takes to get to 75%
1204  if (meas_rate_max < rate_target_max * 0.75f) {
1205  // the measurement not reached the 75% threshold yet
1208  }
1209 
1210  if (meas_rate_max > rate_target_max) {
1211  // the measured rate has passed the maximum target rate
1212  step = UPDATE_GAINS;
1213  }
1214 
1215  if (meas_rate_max-meas_rate_min > meas_rate_max*g.autotune_aggressiveness) {
1216  // the measurement has passed 50% of the maximum rate and bounce back is larger than the threshold
1217  step = UPDATE_GAINS;
1218  }
1219 
1220  if (millis() >= step_stop_time) {
1221  // we have passed the maximum stop time
1222  step = UPDATE_GAINS;
1223  }
1224 }
1225 
1226 // twitching_test_angle - twitching tests
1227 // update min and max and test for end conditions
1228 void Copter::ModeAutoTune::twitching_test_angle(float angle, float rate, float angle_target_max, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max)
1229 {
1230  // capture maximum angle
1231  if (angle > meas_angle_max) {
1232  // the angle still increasing
1233  meas_angle_max = angle;
1234  meas_angle_min = angle;
1235  }
1236 
1237  // capture minimum angle after we have reached a reasonable maximum angle
1238  if ((angle < meas_angle_min) && (meas_angle_max > angle_target_max * 0.5f)) {
1239  // the measurement is bouncing back
1240  meas_angle_min = angle;
1241  }
1242 
1243  // capture maximum rate
1244  if (rate > meas_rate_max) {
1245  // the measurement is still increasing
1246  meas_rate_max = rate;
1247  meas_rate_min = rate;
1248  }
1249 
1250  // capture minimum rate after we have reached maximum rate
1251  if (rate < meas_rate_min) {
1252  // the measurement is still decreasing
1253  meas_rate_min = rate;
1254  }
1255 
1256  // calculate early stopping time based on the time it takes to get to 75%
1257  if (meas_angle_max < angle_target_max * 0.75f) {
1258  // the measurement not reached the 75% threshold yet
1261  }
1262 
1263  if (meas_angle_max > angle_target_max) {
1264  // the measurement has passed the maximum angle
1265  step = UPDATE_GAINS;
1266  }
1267 
1268  if (meas_angle_max-meas_angle_min > meas_angle_max*g.autotune_aggressiveness) {
1269  // the measurement has passed 50% of the maximum angle and bounce back is larger than the threshold
1270  step = UPDATE_GAINS;
1271  }
1272 
1273  if (millis() >= step_stop_time) {
1274  // we have passed the maximum stop time
1275  step = UPDATE_GAINS;
1276  }
1277 }
1278 
1279 // twitching_measure_acceleration - measure rate of change of measurement
1280 void Copter::ModeAutoTune::twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max)
1281 {
1282  if (rate_measurement_max < rate_measurement) {
1283  rate_measurement_max = rate_measurement;
1284  rate_of_change = (1000.0f*rate_measurement_max)/(millis() - step_start_time);
1285  }
1286 }
1287 
1288 // updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back
1289 // optimize D term while keeping the maximum just below the target by adjusting P
1290 void Copter::ModeAutoTune::updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
1291 {
1292  if (meas_rate_max > rate_target) {
1293  // if maximum measurement was higher than target
1294  // reduce P gain (which should reduce maximum)
1295  tune_p -= tune_p*tune_p_step_ratio;
1296  if (tune_p < tune_p_min) {
1297  // P gain is at minimum so start reducing D
1298  tune_p = tune_p_min;
1299  tune_d -= tune_d*tune_d_step_ratio;
1300  if (tune_d <= tune_d_min) {
1301  // We have reached minimum D gain so stop tuning
1302  tune_d = tune_d_min;
1305  }
1306  }
1307  }else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
1308  // we have not achieved a high enough maximum to get a good measurement of bounce back.
1309  // increase P gain (which should increase maximum)
1310  tune_p += tune_p*tune_p_step_ratio;
1311  if (tune_p >= tune_p_max) {
1312  tune_p = tune_p_max;
1314  }
1315  }else{
1316  // we have a good measurement of bounce back
1317  if (meas_rate_max-meas_rate_min > meas_rate_max*g.autotune_aggressiveness) {
1318  // ignore the next result unless it is the same as this one
1319  ignore_next = true;
1320  // bounce back is bigger than our threshold so increment the success counter
1321  counter++;
1322  }else{
1323  if (ignore_next == false) {
1324  // bounce back is smaller than our threshold so decrement the success counter
1325  if (counter > 0 ) {
1326  counter--;
1327  }
1328  // increase D gain (which should increase bounce back)
1329  tune_d += tune_d*tune_d_step_ratio*2.0f;
1330  // stop tuning if we hit maximum D
1331  if (tune_d >= tune_d_max) {
1332  tune_d = tune_d_max;
1335  }
1336  } else {
1337  ignore_next = false;
1338  }
1339  }
1340  }
1341 }
1342 
1343 // updating_rate_d_down - decrease D and adjust P to optimize the D term for no bounce back
1344 // optimize D term while keeping the maximum just below the target by adjusting P
1345 void Copter::ModeAutoTune::updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
1346 {
1347  if (meas_rate_max > rate_target) {
1348  // if maximum measurement was higher than target
1349  // reduce P gain (which should reduce maximum)
1350  tune_p -= tune_p*tune_p_step_ratio;
1351  if (tune_p < tune_p_min) {
1352  // P gain is at minimum so start reducing D gain
1353  tune_p = tune_p_min;
1354  tune_d -= tune_d*tune_d_step_ratio;
1355  if (tune_d <= tune_d_min) {
1356  // We have reached minimum D so stop tuning
1357  tune_d = tune_d_min;
1360  }
1361  }
1362  }else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) {
1363  // we have not achieved a high enough maximum to get a good measurement of bounce back.
1364  // increase P gain (which should increase maximum)
1365  tune_p += tune_p*tune_p_step_ratio;
1366  if (tune_p >= tune_p_max) {
1367  tune_p = tune_p_max;
1369  }
1370  }else{
1371  // we have a good measurement of bounce back
1372  if (meas_rate_max-meas_rate_min < meas_rate_max*g.autotune_aggressiveness) {
1373  if (ignore_next == false) {
1374  // bounce back is less than our threshold so increment the success counter
1375  counter++;
1376  } else {
1377  ignore_next = false;
1378  }
1379  }else{
1380  // ignore the next result unless it is the same as this one
1381  ignore_next = true;
1382  // bounce back is larger than our threshold so decrement the success counter
1383  if (counter > 0 ) {
1384  counter--;
1385  }
1386  // decrease D gain (which should decrease bounce back)
1387  tune_d -= tune_d*tune_d_step_ratio;
1388  // stop tuning if we hit minimum D
1389  if (tune_d <= tune_d_min) {
1390  tune_d = tune_d_min;
1393  }
1394  }
1395  }
1396 }
1397 
1398 // updating_rate_p_up_d_down - increase P to ensure the target is reached while checking bounce back isn't increasing
1399 // P is increased until we achieve our target within a reasonable time while reducing D if bounce back increases above the threshold
1400 void Copter::ModeAutoTune::updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
1401 {
1402  if (meas_rate_max > rate_target*(1+0.5f*g.autotune_aggressiveness)) {
1403  // ignore the next result unless it is the same as this one
1404  ignore_next = true;
1405  // if maximum measurement was greater than target so increment the success counter
1406  counter++;
1407  } else if ((meas_rate_max < rate_target) && (meas_rate_max > rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (meas_rate_max-meas_rate_min > meas_rate_max*g.autotune_aggressiveness) && (tune_d > tune_d_min)) {
1408  // if bounce back was larger than the threshold so decrement the success counter
1409  if (counter > 0 ) {
1410  counter--;
1411  }
1412  // decrease D gain (which should decrease bounce back)
1413  tune_d -= tune_d*tune_d_step_ratio;
1414  // do not decrease the D term past the minimum
1415  if (tune_d <= tune_d_min) {
1416  tune_d = tune_d_min;
1418  }
1419  // decrease P gain to match D gain reduction
1420  tune_p -= tune_p*tune_p_step_ratio;
1421  // do not decrease the P term past the minimum
1422  if (tune_p <= tune_p_min) {
1423  tune_p = tune_p_min;
1425  }
1426  // cancel change in direction
1428  }else{
1429  if (ignore_next == false) {
1430  // if maximum measurement was lower than target so decrement the success counter
1431  if (counter > 0 ) {
1432  counter--;
1433  }
1434  // increase P gain (which should increase the maximum)
1435  tune_p += tune_p*tune_p_step_ratio;
1436  // stop tuning if we hit maximum P
1437  if (tune_p >= tune_p_max) {
1438  tune_p = tune_p_max;
1441  }
1442  } else {
1443  ignore_next = false;
1444  }
1445  }
1446 }
1447 
1448 // updating_angle_p_down - decrease P until we don't reach the target before time out
1449 // P is decreased to ensure we are not overshooting the target
1450 void Copter::ModeAutoTune::updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
1451 {
1452  if (meas_angle_max < angle_target*(1+0.5f*g.autotune_aggressiveness)) {
1453  if (ignore_next == false) {
1454  // if maximum measurement was lower than target so increment the success counter
1455  counter++;
1456  } else {
1457  ignore_next = false;
1458  }
1459  }else{
1460  // ignore the next result unless it is the same as this one
1461  ignore_next = true;
1462  // if maximum measurement was higher than target so decrement the success counter
1463  if (counter > 0 ) {
1464  counter--;
1465  }
1466  // decrease P gain (which should decrease the maximum)
1467  tune_p -= tune_p*tune_p_step_ratio;
1468  // stop tuning if we hit maximum P
1469  if (tune_p <= tune_p_min) {
1470  tune_p = tune_p_min;
1473  }
1474  }
1475 }
1476 
1477 // updating_angle_p_up - increase P to ensure the target is reached
1478 // P is increased until we achieve our target within a reasonable time
1479 void Copter::ModeAutoTune::updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
1480 {
1481  if ((meas_angle_max > angle_target*(1+0.5f*g.autotune_aggressiveness)) ||
1482  ((meas_angle_max > angle_target) && (meas_rate_min < -meas_rate_max*g.autotune_aggressiveness))) {
1483  // ignore the next result unless it is the same as this one
1484  ignore_next = true;
1485  // if maximum measurement was greater than target so increment the success counter
1486  counter++;
1487  }else{
1488  if (ignore_next == false) {
1489  // if maximum measurement was lower than target so decrement the success counter
1490  if (counter > 0 ) {
1491  counter--;
1492  }
1493  // increase P gain (which should increase the maximum)
1494  tune_p += tune_p*tune_p_step_ratio;
1495  // stop tuning if we hit maximum P
1496  if (tune_p >= tune_p_max) {
1497  tune_p = tune_p_max;
1500  }
1501  } else {
1502  ignore_next = false;
1503  }
1504  }
1505 }
1506 
1507 // get attitude for slow position hold in autotune mode
1508 void Copter::ModeAutoTune::get_poshold_attitude(float &roll_cd_out, float &pitch_cd_out, float &yaw_cd_out)
1509 {
1510  roll_cd_out = pitch_cd_out = 0;
1511 
1512  if (!use_poshold) {
1513  // we are not trying to hold position
1514  return;
1515  }
1516 
1517  // do we know where we are?
1518  if (!copter.position_ok()) {
1519  return;
1520  }
1521 
1522  if (!have_position) {
1523  have_position = true;
1525  }
1526 
1527  // don't go past 10 degrees, as autotune result would deteriorate too much
1528  const float angle_max_cd = 1000;
1529 
1530  // hit the 10 degree limit at 20 meters position error
1531  const float dist_limit_cm = 2000;
1532 
1533  // we only start adjusting yaw if we are more than 5m from the
1534  // target position. That corresponds to a lean angle of 2.5 degrees
1535  const float yaw_dist_limit_cm = 500;
1536 
1538  pdiff.z = 0;
1539  float dist_cm = pdiff.length();
1540  if (dist_cm < 10) {
1541  // don't do anything within 10cm
1542  return;
1543  }
1544 
1545  /*
1546  very simple linear controller
1547  */
1548  float scaling = constrain_float(angle_max_cd * dist_cm / dist_limit_cm, 0, angle_max_cd);
1549  Vector2f angle_ne(pdiff.x, pdiff.y);
1550  angle_ne *= scaling / dist_cm;
1551 
1552  // rotate into body frame
1553  pitch_cd_out = angle_ne.x * ahrs.cos_yaw() + angle_ne.y * ahrs.sin_yaw();
1554  roll_cd_out = angle_ne.x * ahrs.sin_yaw() - angle_ne.y * ahrs.cos_yaw();
1555 
1556  if (dist_cm < yaw_dist_limit_cm) {
1557  // no yaw adjustment
1558  return;
1559  }
1560 
1561  /*
1562  also point so that twitching occurs perpendicular to the wind,
1563  if we have drifted more than yaw_dist_limit_cm from the desired
1564  position. This ensures that autotune doesn't have to deal with
1565  more than 2.5 degrees of attitude on the axis it is tuning
1566  */
1567  float target_yaw_cd = degrees(atan2f(pdiff.y, pdiff.x)) * 100;
1568  if (axis == PITCH) {
1569  // for roll and yaw tuning we point along the wind, for pitch
1570  // we point across the wind
1571  target_yaw_cd += 9000;
1572  }
1573  // go to the nearest 180 degree mark, with 5 degree slop to prevent oscillation
1574  if (fabsf(yaw_cd_out - target_yaw_cd) > 9500) {
1575  target_yaw_cd += 18000;
1576  }
1577 
1578  yaw_cd_out = target_yaw_cd;
1579 }
1580 
1581 #endif // AUTOTUNE_ENABLED == ENABLED
void reset(float value)
#define AUTOTUNE_RLPF_MIN
float cos_yaw() const
float scaling
DESIRED_SPIN_WHEN_ARMED
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
bool positive_direction
Definition: Copter.h:497
virtual float get_velocity_z() const=0
void get_poshold_attitude(float &roll_cd, float &pitch_cd, float &yaw_cd)
bool start(bool ignore_checks)
void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
AP_Int8 autotune_axis_bitmask
Definition: Parameters.h:478
#define AUTOTUNE_TARGET_ANGLE_RLLPIT_CD
#define AUTOTUNE_SP_MAX
virtual const Vector3f & get_position() const=0
#define AUTOTUNE_TARGET_ANGLE_YAW_CD
#define AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD
virtual const Vector3f & get_gyro(void) const=0
#define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS
#define FALLTHROUGH
float sin_yaw() const
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
Definition: Log.cpp:24
#define AUTOTUNE_LEVEL_RATE_Y_CD
void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max)
bool twitch_first_iter
Definition: Copter.h:501
float test_angle_min
Definition: Copter.h:510
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: mode.cpp:617
uint32_t override_time
Definition: Copter.h:507
bool check_level(const enum LEVEL_ISSUE issue, const float current, const float maximum)
void update_z_controller()
void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max)
GCS_Copter & gcs()
Definition: mode.cpp:587
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
Definition: Log.cpp:50
void Log_Write_Event(uint8_t id)
Definition: mode.cpp:592
#define AUTOTUNE_SUCCESS_COUNT
#define AUTOTUNE_TESTING_STEP_TIMEOUT_MS
struct Copter::ModeAutoTune::@8 level_problem
#define AUTOTUNE_SP_MIN
uint16_t get_pilot_speed_dn(void)
Definition: mode.cpp:622
void update_simple_mode(void)
Definition: mode.cpp:573
#define AUTOTUNE_RP_ACCEL_MIN
#define AUTOTUNE_MESSAGE_SAVED_GAINS
#define AUTOTUNE_MESSAGE_STARTED
#define AUTOTUNE_LEVEL_ANGLE_CD
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
#define AUTOTUNE_TARGET_RATE_RLLPIT_CDS
float orig_yaw_accel
Definition: Copter.h:525
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
float get_pilot_desired_climb_rate(float throttle_control)
Definition: mode.cpp:558
#define AUTOTUNE_RP_MIN
float tune_roll_accel
Definition: Copter.h:529
#define AUTOTUNE_PI_RATIO_FOR_TESTING
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
#define AUTOTUNE_RP_MAX
#define AUTOTUNE_RD_MAX
#define DATA_AUTOTUNE_OFF
Definition: defines.h:353
AP_Float autotune_aggressiveness
Definition: Parameters.h:479
AP_Int16 pilot_accel_z
Definition: Parameters.h:417
#define MIN(a, b)
int32_t roll_sensor
#define AUTOTUNE_TARGET_MIN_RATE_YAW_CDS
void set_cutoff_frequency(float cutoff_freq)
#define AUTOTUNE_ACCEL_RP_BACKOFF
#define ToDeg(x)
#define DATA_AUTOTUNE_PILOT_TESTING
Definition: defines.h:358
#define DATA_AUTOTUNE_SAVEDGAINS
Definition: defines.h:359
void twitching_test_rate(float rate, float rate_target, float &meas_rate_min, float &meas_rate_max)
#define AUTOTUNE_ACCEL_Y_BACKOFF
LEVEL_ISSUE issue
Definition: Copter.h:539
TuneType tune_type
Definition: Copter.h:499
bool is_active_z() const
float orig_roll_accel
Definition: Copter.h:523
#define AUTOTUNE_ANNOUNCE_INTERVAL_MS
float tune_pitch_accel
Definition: Copter.h:530
void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max)
int16_t get_control_in() const
void relax_alt_hold_controllers(float throttle_setting)
int32_t pitch_sensor
bool is_zero(const T fVal1)
#define f(i)
void updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
#define DATA_AUTOTUNE_SUCCESS
Definition: defines.h:355
#define AUTOTUNE_TARGET_MIN_ANGLE_RLLPIT_CD
#define AUTOTUNE_RD_STEP
float test_accel_max
Definition: Copter.h:518
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
uint32_t millis()
#define AUTOTUNE_AXIS_BITMASK_YAW
#define AUTOTUNE_SP_BACKOFF
bool orig_bf_feedforward
Definition: Copter.h:526
#define AUTOTUNE_RP_BACKOFF
void set_throttle_takeoff(void)
Definition: mode.cpp:597
uint32_t step_stop_time
Definition: Copter.h:513
Vector3f start_position
Definition: Copter.h:504
const char * level_issue_string() const
uint32_t announce_time
Definition: Copter.h:533
float tune_yaw_accel
Definition: Copter.h:531
void set_accel_z(float accel_cmss)
#define AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS
Definition: defines.h:97
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define AUTOTUNE_REQUIRED_LEVEL_TIME_MS
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
bool init(bool ignore_checks) override
DESIRED_THROTTLE_UNLIMITED
#define AUTOTUNE_RP_STEP
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
AC_PosControl *& pos_control
Definition: Copter.h:120
#define AUTOTUNE_D_UP_DOWN_MARGIN
void update_gcs(uint8_t message_id)
#define AUTOTUNE_MESSAGE_FAILED
float length(void) const
#define AUTOTUNE_Y_FILT_FREQ
void run() override
void updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
float constrain_float(const float amt, const float low, const float high)
const char * type_string() const
AP_Float autotune_min_d
Definition: Parameters.h:480
MOTOR_CLASS *& motors
Definition: Copter.h:124
#define AUTOTUNE_PI_RATIO_FINAL
void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max)
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define AUTOTUNE_Y_ACCEL_MIN
float & G_Dt
Definition: Copter.h:129
#define AUTOTUNE_AXIS_BITMASK_PITCH
#define DATA_AUTOTUNE_REACHED_LIMIT
Definition: defines.h:357
#define DATA_AUTOTUNE_RESTART
Definition: defines.h:354
#define AUTOTUNE_TARGET_RATE_YAW_CDS
#define AUTOTUNE_RD_BACKOFF
LowPassFilterFloat rotation_rate_filt
Definition: Copter.h:520
AP_InertialNav & inertial_nav
Definition: Copter.h:121
#define AUTOTUNE_MESSAGE_SUCCESS
#define AUTOTUNE_AXIS_BITMASK_ROLL
#define degrees(x)
float orig_pitch_accel
Definition: Copter.h:524
#define DATA_AUTOTUNE_INITIALISED
Definition: defines.h:352
float test_angle_max
Definition: Copter.h:511
AP_AHRS & ahrs
Definition: Copter.h:122
#define AUTOTUNE_LEVEL_RATE_RP_CD
RC_Channel *& channel_yaw
Definition: Copter.h:128
static struct notify_events_type events
#define AUTOTUNE_SP_STEP
#define AUTOTUNE_YAW_PI_RATIO_FINAL
int32_t yaw_sensor
uint32_t step_start_time
Definition: Copter.h:512
Parameters & g
Definition: Copter.h:116
#define AUTOTUNE_RLPF_MAX
void set_land_complete(bool b)
Definition: mode.cpp:582
RC_Channel *& channel_throttle
Definition: Copter.h:127
#define AUTOTUNE_MESSAGE_STOPPED
float apply(float sample, float dt)
void set_alt_target_to_current_alt()