mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: Support landing flight termination
This commit is contained in:
parent
4fd13d5205
commit
ffc2aeee32
@ -17,20 +17,24 @@ AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission, AP_
|
|||||||
*/
|
*/
|
||||||
void AP_AdvancedFailsafe_Copter::terminate_vehicle(void)
|
void AP_AdvancedFailsafe_Copter::terminate_vehicle(void)
|
||||||
{
|
{
|
||||||
// stop motors
|
if (_terminate_action == TERMINATE_ACTION_LAND) {
|
||||||
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
copter.set_mode(LAND, MODE_REASON_TERMINATE);
|
||||||
copter.motors->output();
|
} else {
|
||||||
|
// stop motors
|
||||||
|
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
|
||||||
|
copter.motors->output();
|
||||||
|
|
||||||
// disarm as well
|
// disarm as well
|
||||||
copter.init_disarm_motors();
|
copter.init_disarm_motors();
|
||||||
|
|
||||||
// and set all aux channels
|
// and set all aux channels
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_heli_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
SRV_Channels::set_output_limit(SRV_Channel::k_heli_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_heli_tail_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
SRV_Channels::set_output_limit(SRV_Channel::k_heli_tail_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, 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_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();
|
||||||
}
|
}
|
||||||
|
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user