mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 08:44:08 -04:00
AP_Baro: skip cal on watchdog reset
This commit is contained in:
parent
7e675805fa
commit
3cb134b67c
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user