Browse Source

Plane: apply throttle slew to dual-motor setups

thanks to Alex for noticing this issue
master
Andrew Tridgell 6 years ago
parent
commit
6c7af3830b
  1. 2
      ArduPlane/servos.cpp

2
ArduPlane/servos.cpp

@ -35,6 +35,8 @@ void Plane::throttle_slew_limit(void) @@ -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…
Cancel
Save