From b0311c4ef38dc6f8bb4926bed8f3b57d290af8ff Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 10 May 2017 14:32:26 +0900 Subject: [PATCH] Copter: ensure esc calibration only occurs on next reboot It was possible for a board with no safety switch attached to get stuck waiting for the user to press the non-existance switch. Rebooting now resolves the problem because the ESC_CAL parameter is reset to zero regardless of whether the calibration completes or not. --- ArduCopter/esc_calibration.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index b5c068c473..0579521678 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -125,6 +125,9 @@ void Copter::esc_calibration_auto() #if FRAME_CONFIG != HELI_FRAME bool printed_msg = false; + // clear esc flag for next time + g.esc_calibrate.set_and_save(ESCCAL_NONE); + if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) { // run at full speed for oneshot ESCs (actually done on push) motors->set_update_rate(g.rc_speed); @@ -169,9 +172,6 @@ void Copter::esc_calibration_auto() // reduce throttle to minimum motors->set_throttle_passthrough_for_esc_calibration(0.0f); - // clear esc parameter - g.esc_calibrate.set_and_save(ESCCAL_NONE); - // block until we restart while(1) { motors->set_throttle_passthrough_for_esc_calibration(0.0f);