mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: use throttle slew when in quadplane assisted flight
this prevents a sudden throttle change on a petrol motor when transitioning
This commit is contained in:
parent
12fab6c59a
commit
8ecf54bf75
@ -1023,7 +1023,8 @@ void Plane::set_servos(void)
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap_auto, auto_flap_percent);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap, manual_flap_percent);
|
||||
|
||||
if (control_mode >= FLY_BY_WIRE_B) {
|
||||
if (control_mode >= FLY_BY_WIRE_B ||
|
||||
quadplane.in_assisted_flight()) {
|
||||
/* only do throttle slew limiting in modes where throttle
|
||||
* control is automatic */
|
||||
throttle_slew_limit(last_throttle);
|
||||
|
Loading…
Reference in New Issue
Block a user