From b6809655d45b62d538431705eb68f892378d3d16 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Sep 2017 16:43:32 +1000 Subject: [PATCH] Plane: smooth the transition to LAND_FINAL in quadplanes this makes for a much smoother change to LAND_FINAL, without a jerk as it changes vertical speed --- ArduPlane/quadplane.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 621f916459..1555a838aa 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -920,7 +920,7 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground) { float ret = linear_interpolate(land_speed_cms, wp_nav->get_speed_down(), height_above_ground, - land_final_alt, land_final_alt+3); + land_final_alt, land_final_alt+6); return ret; } @@ -2123,7 +2123,6 @@ bool QuadPlane::verify_vtol_land(void) float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); if (poscontrol.state == QPOS_LAND_DESCEND && height_above_ground < land_final_alt) { poscontrol.state = QPOS_LAND_FINAL; - set_alt_target_current(); // cut IC engine if enabled if (land_icengine_cut != 0) {