mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: fixed throttle when terminated
thanks to Michael Thomas for reporting this
This commit is contained in:
parent
af510801f1
commit
aa1548e404
@ -26,6 +26,7 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
|||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, SERVO_MAX);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, SERVO_MAX);
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, SERVO_MAX);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, SERVO_MAX);
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, SERVO_MAX);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, SERVO_MAX);
|
||||||
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_manual, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
SRV_Channels::set_output_limit(SRV_Channel::k_manual, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_none, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
SRV_Channels::set_output_limit(SRV_Channel::k_none, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user