From 73928b82a6c3b3dd54ca5c4b52ddf30c886f7d4c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Jul 2013 11:58:40 +1000 Subject: [PATCH] Plane: fixed FBWB airspeed control thanks to Gabor for reporting this! --- ArduPlane/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/navigation.pde b/ArduPlane/navigation.pde index 9e92ad2012..61a6823c2c 100644 --- a/ArduPlane/navigation.pde +++ b/ArduPlane/navigation.pde @@ -87,7 +87,7 @@ static void calc_airspeed_errors() if (control_mode == FLY_BY_WIRE_B) { target_airspeed_cm = ((int32_t)(aparm.flybywire_airspeed_max - aparm.flybywire_airspeed_min) * - channel_throttle->servo_out) + + channel_throttle->control_in) + ((int32_t)aparm.flybywire_airspeed_min * 100); }