throttle: only use throttle slew in auto throttle modes

we don't want STABILISE and FBWA to have throttle change limits
This commit is contained in:
Andrew Tridgell 2011-12-10 22:05:07 +11:00
parent fa683c5718
commit 4319d1ceb0

View File

@ -361,7 +361,11 @@ static void set_servos(void)
#endif
*/
throttle_slew_limit();
if (control_mode >= FLY_BY_WIRE_B) {
/* only do throttle slew limiting in modes where throttle
control is automatic */
throttle_slew_limit();
}
}
// Auto flap deployment