diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index b8c498483ac05e..809ca03c0e931d 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -41,7 +41,7 @@ void Compass::cal_update() return; } else if (_cal_has_run && _auto_reboot()) { hal.scheduler->delay(1000); - hal.scheduler->reboot(false); + hal.scheduler->reboot(); } }