From f183a2618f7cc80da8d1858cbc897e0ab41bef3a Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sun, 29 Jan 2017 22:16:58 -0700 Subject: [PATCH] Plane: Don't lock home altitude to AHRS origin --- ArduPlane/commands.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index 0cef7fe650..24b3e4fc94 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -137,16 +137,9 @@ void Plane::update_home() } if (home_is_set == HOME_SET_NOT_LOCKED) { Location loc = gps.location(); - Location origin; - // if an EKF origin is available then we leave home equal to - // the height of that origin. This ensures that our relative - // height calculations are using the same origin - if (ahrs.get_origin(origin)) { - loc.alt = origin.alt; - } ahrs.set_home(loc); Log_Write_Home_And_Origin(); - GCS_MAVLINK::send_home_all(gps.location()); + GCS_MAVLINK::send_home_all(loc); } barometer.update_calibration(); }