mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: reset baro drift when setting home while disarmed
This commit is contained in:
parent
472dae3ed9
commit
4a6dd5a781
@ -472,6 +472,9 @@ void Plane::update_GPS_10Hz(void)
|
||||
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
update_home();
|
||||
|
||||
// zero out any baro drift
|
||||
barometer.set_baro_drift_altitude(0);
|
||||
}
|
||||
|
||||
// update wind estimate
|
||||
|
Loading…
Reference in New Issue
Block a user