From 82f68464d48974db4d4c5f7eb6213984596dca17 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sat, 13 Jun 2020 08:28:29 +1000 Subject: [PATCH] Plane: Don't lower nose when hand launching --- ArduPlane/takeoff.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 90165e4c66..492ba6324c 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -168,8 +168,14 @@ void Plane::takeoff_calc_pitch(void) nav_pitch_cd = takeoff_pitch_min_cd; } } else { - nav_pitch_cd = ((gps.ground_speed()*100) / (float)aparm.airspeed_cruise_cm) * auto_state.takeoff_pitch_cd; - nav_pitch_cd = constrain_int32(nav_pitch_cd, 500, auto_state.takeoff_pitch_cd); + if (is_positive(g.takeoff_throttle_min_speed) || is_positive(g.takeoff_throttle_min_accel)) { + // Doing hand launch so don't lower pitch when low ground speed + nav_pitch_cd = MIN(auto_state.takeoff_pitch_cd, 500); + } else { + // Rise off ground takeoff so delay rotation until ground speed indicates adequate airspeed + nav_pitch_cd = ((gps.ground_speed()*100) / (float)aparm.airspeed_cruise_cm) * auto_state.takeoff_pitch_cd; + nav_pitch_cd = constrain_int32(nav_pitch_cd, 500, auto_state.takeoff_pitch_cd); + } } if (aparm.stall_prevention != 0) {