From d0913111967e265e20e1b82000a0d9c6b672c4d1 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Wed, 22 Aug 2012 16:27:58 +1000
Subject: [PATCH] APM: removed factor of 0.5 in non-airspeed takeoff pitch

this limited the pitch far below the specified target pitch
---
 ArduPlane/ArduPlane.pde | 7 +++----
 1 file changed, 3 insertions(+), 4 deletions(-)

diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 3b5ed6735..343381d54 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -1075,13 +1075,12 @@ static void update_current_flight_mode(void)
                 if (nav_pitch_cd < takeoff_pitch_cd)
                     nav_pitch_cd = takeoff_pitch_cd;
             } else {
-                nav_pitch_cd = (float)g_gps->ground_speed / (float)g.airspeed_cruise_cm * (float)takeoff_pitch_cd * 0.5;
+                nav_pitch_cd = (g_gps->ground_speed / (float)g.airspeed_cruise_cm) * takeoff_pitch_cd;
                 nav_pitch_cd = constrain(nav_pitch_cd, 500, takeoff_pitch_cd);
             }
 
-            g.channel_throttle.servo_out = g.throttle_max;                     //TODO: Replace with THROTTLE_TAKEOFF or other method of controlling throttle
-            //  What is the case for doing something else?  Why wouldn't you want max throttle for TO?
-            // ******************************
+            // max throttle for takeoff
+            g.channel_throttle.servo_out = g.throttle_max;
 
             break;
 
-- 
GitLab