Browse Source

AP_InertialSensor: fix accelcalsimple watchdog

mission-4.1.18
Jaaaky 6 years ago committed by Andrew Tridgell
parent
commit
47c65314fb
  1. 3
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

3
libraries/AP_InertialSensor/AP_InertialSensor.cpp

@ -1860,6 +1860,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() @@ -1860,6 +1860,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;
@ -1999,6 +2000,8 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() @@ -1999,6 +2000,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…
Cancel
Save