From f29951c2bf5019ab9de433e8c167bb3e099ca9ce Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 21 Jun 2017 18:05:45 +0900 Subject: [PATCH] Copter: fix autotune accel max not being used until reboot Once autotune completes successfully, the discovered acceleration maximums should be used if the pilot tests the tune --- ArduCopter/control_autotune.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index 1d6f31a991..3afda21c49 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -1169,6 +1169,7 @@ void Copter::autotune_save_tuning_gains() orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); orig_roll_rd = attitude_control->get_rate_roll_pid().kD(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); + orig_roll_accel = attitude_control->get_accel_roll_max(); } if (autotune_pitch_enabled() && !is_zero(tune_pitch_rp)) { @@ -1190,6 +1191,7 @@ void Copter::autotune_save_tuning_gains() orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); + orig_pitch_accel = attitude_control->get_accel_pitch_max(); } if (autotune_yaw_enabled() && !is_zero(tune_yaw_rp)) { @@ -1213,6 +1215,7 @@ void Copter::autotune_save_tuning_gains() orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_hz(); orig_yaw_sp = attitude_control->get_angle_yaw_p().kP(); + orig_yaw_accel = attitude_control->get_accel_pitch_max(); } // update GCS and log save gains event autotune_update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);