mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: fixed FBWB airspeed control
thanks to Gabor for reporting this!
This commit is contained in:
parent
1d04290eab
commit
73928b82a6
@ -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…
Reference in New Issue
Block a user