mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
AP_InertialSensor: prevent watchdog in accelcal
This commit is contained in:
parent
020ce245b9
commit
12dfccf65a
@ -1106,6 +1106,8 @@ AP_InertialSensor::_init_gyro()
|
|||||||
// cold start
|
// cold start
|
||||||
hal.console->printf("Init Gyro");
|
hal.console->printf("Init Gyro");
|
||||||
|
|
||||||
|
hal.scheduler->expect_delay_ms(60000);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
we do the gyro calibration with no board rotation. This avoids
|
we do the gyro calibration with no board rotation. This avoids
|
||||||
having to rotate readings during the calibration
|
having to rotate readings during the calibration
|
||||||
@ -1220,6 +1222,8 @@ AP_InertialSensor::_init_gyro()
|
|||||||
|
|
||||||
// stop flashing leds
|
// stop flashing leds
|
||||||
AP_Notify::flags.initialising = false;
|
AP_Notify::flags.initialising = false;
|
||||||
|
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// save parameters to eeprom
|
// save parameters to eeprom
|
||||||
@ -1681,11 +1685,13 @@ void AP_InertialSensor::acal_update()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
hal.scheduler->expect_delay_ms(20000);
|
||||||
_acal->update();
|
_acal->update();
|
||||||
|
|
||||||
if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
|
if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
|
||||||
_acal->cancel();
|
_acal->cancel();
|
||||||
}
|
}
|
||||||
|
hal.scheduler->expect_delay_ms(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user