diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index bc2e82f105..fee5120a13 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -44,7 +44,7 @@ void Copter::init_rc_in() ap.throttle_zero = true; } - // init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration + // init_rc_out -- initialise motors void Copter::init_rc_out() { motors->set_loop_rate(scheduler.get_loop_rate_hz()); @@ -74,9 +74,6 @@ void Copter::init_rc_out() uint16_t safety_ignore_mask = (~copter.motors->get_motor_mask()) & 0x3FFF; BoardConfig.set_default_safety_ignore_mask(safety_ignore_mask); #endif - - // check if we should enter esc calibration mode - esc_calibration_startup_check(); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index d13c936011..5334c70079 100755 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -117,6 +117,9 @@ void Copter::init_ardupilot() // sets up motors and output to escs init_rc_out(); + // check if we should enter esc calibration mode + esc_calibration_startup_check(); + // motors initialised so parameters can be sent ap.initialised_params = true;