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