mirror of https://github.com/ArduPilot/ardupilot
Plane: handle twin motor planes for AFS failsafe
This commit is contained in:
parent
8c33b4b97d
commit
455f15a157
|
@ -27,6 +27,8 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
|||
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_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, 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_none, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||
}
|
||||
|
@ -47,6 +49,9 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void)
|
|||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_aileron, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_elevator, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleRight, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_manual, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||
SRV_Channels::set_failsafe_limit(SRV_Channel::k_none, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||
|
||||
|
|
Loading…
Reference in New Issue