2016-08-16 07:23:27 -03:00
|
|
|
/*
|
|
|
|
copter specific AP_AdvancedFailsafe class
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "Copter.h"
|
|
|
|
|
|
|
|
#if ADVANCED_FAILSAFE == ENABLED
|
|
|
|
|
|
|
|
// Constructor
|
2018-05-05 05:24:07 -03:00
|
|
|
AP_AdvancedFailsafe_Copter::AP_AdvancedFailsafe_Copter(AP_Mission &_mission, const AP_GPS &_gps) :
|
|
|
|
AP_AdvancedFailsafe(_mission, _gps)
|
2016-08-16 07:23:27 -03:00
|
|
|
{}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup radio_out values for all channels to termination values
|
|
|
|
*/
|
|
|
|
void AP_AdvancedFailsafe_Copter::terminate_vehicle(void)
|
|
|
|
{
|
2017-08-30 16:32:00 -03:00
|
|
|
if (_terminate_action == TERMINATE_ACTION_LAND) {
|
|
|
|
copter.set_mode(LAND, MODE_REASON_TERMINATE);
|
|
|
|
} else {
|
|
|
|
// stop motors
|
2019-04-09 09:16:58 -03:00
|
|
|
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
2017-08-30 16:32:00 -03:00
|
|
|
copter.motors->output();
|
|
|
|
|
|
|
|
// disarm as well
|
|
|
|
copter.init_disarm_motors();
|
2016-08-16 07:23:27 -03:00
|
|
|
|
2017-08-30 16:32:00 -03:00
|
|
|
// 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_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_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_manual, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
}
|
2016-08-16 07:23:27 -03:00
|
|
|
|
2017-01-30 10:42:21 -04:00
|
|
|
SRV_Channels::output_ch_all();
|
2016-08-16 07:23:27 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void)
|
|
|
|
{
|
|
|
|
// setup failsafe for all aux channels
|
2017-01-30 10:42:21 -04:00
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_heli_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_heli_tail_rsc, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_ignition, 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::SRV_CHANNEL_LIMIT_TRIM);
|
2016-08-16 07:23:27 -03:00
|
|
|
|
|
|
|
#if FRAME_CONFIG != HELI_FRAME
|
|
|
|
// setup AP_Motors outputs for failsafe
|
2017-01-09 03:31:26 -04:00
|
|
|
uint16_t mask = copter.motors->get_motor_mask();
|
|
|
|
hal.rcout->set_failsafe_pwm(mask, copter.motors->get_pwm_output_min());
|
2016-08-16 07:23:27 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return an AFS_MODE for current control mode
|
|
|
|
*/
|
|
|
|
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void)
|
|
|
|
{
|
|
|
|
switch (copter.control_mode) {
|
|
|
|
case AUTO:
|
|
|
|
case GUIDED:
|
|
|
|
case RTL:
|
|
|
|
case LAND:
|
|
|
|
return AP_AdvancedFailsafe::AFS_AUTO;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return AP_AdvancedFailsafe::AFS_STABILIZED;
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // ADVANCED_FAILSAFE
|