From 600a5c44d2fee0fee4c86893596a45f0791ebe1c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Sep 2017 08:10:07 +1000 Subject: [PATCH] Plane: allow changing of target altitude in GUIDED --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 5ed4ea3948..8ede107de6 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1808,7 +1808,7 @@ void QuadPlane::vtol_position_controller(void) switch (poscontrol.state) { case QPOS_POSITION1: case QPOS_POSITION2: - if (plane.control_mode == QRTL) { + if (plane.control_mode == QRTL || plane.control_mode == GUIDED) { plane.ahrs.get_position(plane.current_loc); float target_altitude = plane.next_WP_loc.alt; if (poscontrol.slow_descent) {