mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: skip cal on watchdog reset
This commit is contained in:
parent
bbe4c92b58
commit
8d57a6a86a
|
@ -183,6 +183,10 @@ AP_Baro::AP_Baro()
|
||||||
// the altitude() or climb_rate() interfaces can be used
|
// the altitude() or climb_rate() interfaces can be used
|
||||||
void AP_Baro::calibrate(bool save)
|
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");
|
gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
|
||||||
|
|
||||||
// reset the altitude offset when we calibrate. The altitude
|
// reset the altitude offset when we calibrate. The altitude
|
||||||
|
|
Loading…
Reference in New Issue