From 034d476fa566cd940de29dec0ebc1ecbdc0d5468 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 abb17366a9..85874f3f31 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1115,6 +1115,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 @@ -1229,6 +1231,8 @@ AP_InertialSensor::_init_gyro() // stop flashing leds AP_Notify::flags.initialising = false; + + hal.scheduler->expect_delay_ms(0); } // save parameters to eeprom @@ -1693,11 +1697,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); } /*