AP_Baro: Fix not healthy by watchdog reset

This commit is contained in:
Jaaaky 2019-05-02 11:56:41 +03:00 committed by Andrew Tridgell
parent 4deb2c38f6
commit 6ed8b2aad9
1 changed files with 6 additions and 6 deletions

View File

@ -183,6 +183,12 @@ AP_Baro::AP_Baro()
// the altitude() or climb_rate() interfaces can be used
void AP_Baro::calibrate(bool save)
{
// start by assuming all sensors are calibrated (for healthy() test)
for (uint8_t i=0; i<_num_sensors; i++) {
sensors[i].calibrated = true;
sensors[i].alt_ok = true;
}
if (hal.util->was_watchdog_reset()) {
gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration");
return;
@ -193,12 +199,6 @@ void AP_Baro::calibrate(bool save)
// offset is supposed to be for within a flight
_alt_offset.set_and_save(0);
// start by assuming all sensors are calibrated (for healthy() test)
for (uint8_t i=0; i<_num_sensors; i++) {
sensors[i].calibrated = true;
sensors[i].alt_ok = true;
}
// let the barometer settle for a full second after startup
// the MS5611 reads quite a long way off for the first second,
// leading to about 1m of error if we don't wait