mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fix accelcalsimple watchdog
This commit is contained in:
parent
6ea22c9cf8
commit
715f117d4b
|
@ -1848,6 +1848,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
|
|||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||
}
|
||||
|
||||
hal.scheduler->expect_delay_ms(20000);
|
||||
// record we are calibrating
|
||||
_calibrating = true;
|
||||
|
||||
|
@ -1987,6 +1988,8 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
|
|||
// stop flashing leds
|
||||
AP_Notify::flags.initialising = false;
|
||||
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue