mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: Support landing terminations on landing backends that support it
This commit is contained in:
parent
0bbbb3d08d
commit
4fd13d5205
@ -17,7 +17,10 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
||||
{
|
||||
plane.g2.servo_channels.disable_passthrough(true);
|
||||
|
||||
// and all aux channels
|
||||
if (_terminate_action == TERMINATE_ACTION_LAND) {
|
||||
plane.landing.terminate();
|
||||
} else {
|
||||
// aerodynamic termination is the default approach to termination
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flap_auto, 100);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_flap, 100);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, SERVO_MAX);
|
||||
@ -25,6 +28,7 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void)
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, SERVO_MAX);
|
||||
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);
|
||||
}
|
||||
|
||||
plane.servos_output();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user