From 8f0e7e0693405d30d05d1ab67d7ae855f1a561ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 Jul 2015 08:20:23 +1000 Subject: [PATCH] Plane: fixed above_location_current() for non-terrain alt thanks to Lekston for finding the bug (PR#2610) --- ArduPlane/altitude.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 66ab26a1a3..5fdc398c39 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -398,8 +398,8 @@ bool Plane::above_location_current(const Location &loc) #endif float loc_alt_cm = loc.alt; - if (!loc.flags.relative_alt) { - loc_alt_cm -= home.alt; + if (loc.flags.relative_alt) { + loc_alt_cm += home.alt; } return current_loc.alt > loc_alt_cm; }