From bdf6471587f30ce30d9ff5ecdd31b148db108fc9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 24 Sep 2011 21:55:54 -0700 Subject: [PATCH] Better throttle boost value --- ArduCopter/Attitude.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 22f3745601..02a762c635 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -220,6 +220,6 @@ static int get_angle_boost() { float temp = cos_pitch_x * cos_roll_x; temp = 1.0 - constrain(temp, .5, 1.0); - return (int)(temp * 60.0); + return (int)(temp * g.throttle_cruise); }