diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index c32f5802a81d6..18062d8d59b23 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -87,6 +87,11 @@ void Plane::setup_glide_slope(void) reset_offset_altitude(); break; } + //descend without doing glide slope if option is enabled + if (above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_DESCEND_IN_AUTO)) { + reset_offset_altitude(); + break; + } // we only do glide slide handling in AUTO when above 20m or // when descending. The 20 meter threshold is arbitrary, and diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index b2939557adfdf..2e6c7f434111c 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -169,6 +169,7 @@ enum FlightOptions { ENABLE_LOITER_ALT_CONTROL = (1<<12), INDICATE_WAITING_FOR_RUDDER_NEUTRAL = (1<<13), IMMEDIATE_CLIMB_IN_AUTO = (1<<14), + IMMEDIATE_DESCEND_IN_AUTO = (1<<15), }; enum CrowFlapOptions {