|
|
|
@ -35,17 +35,17 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
@@ -35,17 +35,17 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, SERVO_MAX); |
|
|
|
|
if (plane.have_reverse_thrust()) { |
|
|
|
|
// configured for reverse thrust, use TRIM
|
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::TRIM); |
|
|
|
|
} else { |
|
|
|
|
// use MIN
|
|
|
|
|
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_throttle, SRV_Channel::Limit::MIN); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::MIN); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, 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); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_manual, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_output_limit(SRV_Channel::k_none, SRV_Channel::Limit::TRIM); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
plane.servos_output(); |
|
|
|
@ -59,24 +59,24 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
@@ -59,24 +59,24 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
|
|
|
|
void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void) |
|
|
|
|
{ |
|
|
|
|
// all aux channels
|
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_flap_auto, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_flap, SRV_Channel::SRV_CHANNEL_LIMIT_MAX); |
|
|
|
|
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_flap_auto, SRV_Channel::Limit::MAX); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_flap, SRV_Channel::Limit::MAX); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_aileron, SRV_Channel::Limit::MIN); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::Limit::MAX); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_elevator, SRV_Channel::Limit::MAX); |
|
|
|
|
if (plane.have_reverse_thrust()) { |
|
|
|
|
// configured for reverse thrust, use TRIM
|
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleLeft, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleRight, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::TRIM); |
|
|
|
|
} else { |
|
|
|
|
// normal throttle, use MIN
|
|
|
|
|
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_throttle, SRV_Channel::Limit::MIN); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::MIN); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttleRight, 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); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_manual, SRV_Channel::Limit::TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_none, SRV_Channel::Limit::TRIM); |
|
|
|
|
|
|
|
|
|
if (plane.quadplane.available()) { |
|
|
|
|
// setup AP_Motors outputs for failsafe
|
|
|
|
|