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:
parent
0a7332b6e3
commit
2bd18e937c
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user