From 0089e98bb6b1ba0077391e6758445316ca203205 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Feb 2019 10:15:47 +1100 Subject: [PATCH] Plane: call AHRS resetHeightDatum() on baro reset this prevents the AMSL estimate from the EKF going off badly if we disarm at a high altitude --- ArduPlane/commands.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index 0cf304ae8a..be26e14b8f 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -124,6 +124,7 @@ void Plane::update_home() } } barometer.update_calibration(); + ahrs.resetHeightDatum(); } void Plane::set_home_persistently(const Location &loc)