Browse Source

AP_Baro: skip cal on watchdog reset

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
8d57a6a86a
  1. 4
      libraries/AP_Baro/AP_Baro.cpp

4
libraries/AP_Baro/AP_Baro.cpp

@ -183,6 +183,10 @@ AP_Baro::AP_Baro() @@ -183,6 +183,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

Loading…
Cancel
Save