Plane: allow changing of target altitude in GUIDED

This commit is contained in:
Andrew Tridgell 2017-09-09 08:10:07 +10:00
parent bc17c26dbf
commit 600a5c44d2
1 changed files with 1 additions and 1 deletions

View File

@ -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) {