AP_Baro: skip cal on watchdog reset

This commit is contained in:
Andrew Tridgell 2019-04-11 19:57:28 +10:00 committed by Randy Mackay
parent 194176ca06
commit 43dfc67b96

View File

@ -163,6 +163,10 @@ AP_Baro::AP_Baro()
// the altitude() or climb_rate() interfaces can be used
void AP_Baro::calibrate(bool save)
{
if (hal.util->was_watchdog_reset()) {
gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration");
return;
}
gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
// reset the altitude offset when we calibrate. The altitude