From 04e5f6b5f66e04bf662208c919e85ad9087ca1ba Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 20 Aug 2023 20:41:34 +1000 Subject: [PATCH] Plane: use forward tilt instead of forward throttle when close to ground --- ArduPlane/quadplane.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 63a0f8711b..25e40a534c 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2941,6 +2941,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) { float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); float fwd_thr_scaler = linear_interpolate(0.0f, 1.0f, height_above_ground, alt_cutoff, alt_cutoff+2); q_fwd_throttle *= fwd_thr_scaler; + q_fwd_nav_pitch_lim_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + 100.0f * q_fwd_pitch_lim * fwd_thr_scaler); } } else {