From 780d1459f0ab58a423a220c089706b6fc87dc02c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Jan 2016 22:23:26 +1100 Subject: [PATCH] Plane: fixed force descend in VTOL land --- ArduPlane/quadplane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 1c3e1f5bb4..6e74286dac 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -868,11 +868,11 @@ void QuadPlane::control_auto(const Location &loc) switch (plane.mission.get_current_nav_cmd().id) { case MAV_CMD_NAV_VTOL_LAND: if (plane.auto_state.wp_distance > 2) { - pos_control->set_alt_target_from_climb_rate_ff(0, plane.G_Dt, true); + pos_control->set_alt_target_from_climb_rate_ff(0, plane.G_Dt, false); } else if (plane.current_loc.alt > plane.next_WP_loc.alt+5*100) { pos_control->set_alt_target_with_slew(wp_nav->get_loiter_target().z, plane.ins.get_loop_delta_t()); } else { - pos_control->set_alt_target_from_climb_rate_ff(-30, plane.G_Dt, false); + pos_control->set_alt_target_from_climb_rate_ff(-30, plane.G_Dt, true); } break; case MAV_CMD_NAV_VTOL_TAKEOFF: