Copter: Support landing flight termination

This commit is contained in:
Michael du Breuil 2017-08-30 12:32:00 -07:00 committed by Tom Pittenger
parent 4fd13d5205
commit ffc2aeee32
2 changed files with 17 additions and 12 deletions

View File

@ -17,6 +17,9 @@ AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission, AP_
*/ */
void AP_AdvancedFailsafe_Copter::terminate_vehicle(void) void AP_AdvancedFailsafe_Copter::terminate_vehicle(void)
{ {
if (_terminate_action == TERMINATE_ACTION_LAND) {
copter.set_mode(LAND, MODE_REASON_TERMINATE);
} else {
// stop motors // stop motors
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN); copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
copter.motors->output(); copter.motors->output();
@ -31,6 +34,7 @@ void AP_AdvancedFailsafe_Copter::terminate_vehicle(void)
SRV_Channels::set_output_limit(SRV_Channel::k_ignition, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); SRV_Channels::set_output_limit(SRV_Channel::k_ignition, 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);
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::output_ch_all(); SRV_Channels::output_ch_all();
} }

View File

@ -124,6 +124,7 @@ enum mode_reason_t {
MODE_REASON_AVOIDANCE, MODE_REASON_AVOIDANCE,
MODE_REASON_AVOIDANCE_RECOVERY, MODE_REASON_AVOIDANCE_RECOVERY,
MODE_REASON_THROW_COMPLETE, MODE_REASON_THROW_COMPLETE,
MODE_REASON_TERMINATE,
}; };
// Tuning enumeration // Tuning enumeration