From 12dfccf65a7616e8200699f8fae963d0d481c45d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Apr 2019 17:21:08 +1000 Subject: [PATCH] AP_InertialSensor: prevent watchdog in accelcal --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index abe556f6e6..5fd4c5f6e8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1106,6 +1106,8 @@ AP_InertialSensor::_init_gyro() // cold start hal.console->printf("Init Gyro"); + hal.scheduler->expect_delay_ms(60000); + /* we do the gyro calibration with no board rotation. This avoids having to rotate readings during the calibration @@ -1220,6 +1222,8 @@ AP_InertialSensor::_init_gyro() // stop flashing leds AP_Notify::flags.initialising = false; + + hal.scheduler->expect_delay_ms(0); } // save parameters to eeprom @@ -1681,11 +1685,13 @@ void AP_InertialSensor::acal_update() return; } + hal.scheduler->expect_delay_ms(20000); _acal->update(); if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) { _acal->cancel(); } + hal.scheduler->expect_delay_ms(0); } /*