diff --git a/ArduPlane/altitude.pde b/ArduPlane/altitude.pde index cd46561504..b6c504e52a 100644 --- a/ArduPlane/altitude.pde +++ b/ArduPlane/altitude.pde @@ -87,7 +87,7 @@ static void setup_glide_slope(void) // is basically to prevent situations where we try to slowly // gain height at low altitudes, potentially hitting // obstacles. - if (relative_altitude() > 20 || above_location_current(next_WP_loc)) { + if (adjusted_relative_altitude_cm() > 2000 || above_location_current(next_WP_loc)) { set_offset_altitude_location(next_WP_loc); } else { reset_offset_altitude();