Browse Source

Plane: fixed FBWB airspeed control

thanks to Gabor for reporting this!
master
Andrew Tridgell 12 years ago
parent
commit
73928b82a6
  1. 2
      ArduPlane/navigation.pde

2
ArduPlane/navigation.pde

@ -87,7 +87,7 @@ static void calc_airspeed_errors() @@ -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);
}

Loading…
Cancel
Save