mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: apply throttle slew to dual-motor setups
thanks to Alex for noticing this issue
This commit is contained in:
parent
45fa3913ec
commit
1a56659eec
@ -35,6 +35,8 @@ void Plane::throttle_slew_limit(void)
|
||||
// if slew limit rate is set to zero then do not slew limit
|
||||
if (slewrate) {
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttle, slewrate, G_Dt);
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleLeft, slewrate, G_Dt);
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_throttleRight, slewrate, G_Dt);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user