diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 1e989a8552..cc8e1bd2d4 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -192,14 +192,6 @@ void Copter::compass_cal_update() compass.compass_cal_update(); } -#ifdef CAL_ALWAYS_REBOOT - if (compass.compass_cal_requires_reboot()) { - hal.scheduler->delay(1000); - hal.scheduler->reboot(false); - return; - } -#endif - if (compass.is_calibrating()) { if (channel_yaw->get_control_in() < -4000 && channel_throttle->get_control_in() > 900) { compass.cancel_calibration_all(); @@ -211,7 +203,11 @@ void Copter::compass_cal_update() if (!stick_gesture_detected) { compass_cal_stick_gesture_begin = tnow; } else if (tnow-compass_cal_stick_gesture_begin > 1000*COMPASS_CAL_STICK_GESTURE_TIME) { +#ifdef CAL_ALWAYS_REBOOT + compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,true); +#else compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,false); +#endif } } }