mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: Fix not healthy by watchdog reset
This commit is contained in:
parent
4deb2c38f6
commit
6ed8b2aad9
|
@ -183,6 +183,12 @@ 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)
|
||||||
{
|
{
|
||||||
|
// 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()) {
|
if (hal.util->was_watchdog_reset()) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration");
|
gcs().send_text(MAV_SEVERITY_INFO, "Baro: skipping calibration");
|
||||||
return;
|
return;
|
||||||
|
@ -193,12 +199,6 @@ void AP_Baro::calibrate(bool save)
|
||||||
// offset is supposed to be for within a flight
|
// offset is supposed to be for within a flight
|
||||||
_alt_offset.set_and_save(0);
|
_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
|
// let the barometer settle for a full second after startup
|
||||||
// the MS5611 reads quite a long way off for the first second,
|
// the MS5611 reads quite a long way off for the first second,
|
||||||
// leading to about 1m of error if we don't wait
|
// leading to about 1m of error if we don't wait
|
||||||
|
|
Loading…
Reference in New Issue