2015-05-29 23:12:49 -03:00
# include "Copter.h"
2011-02-17 03:28:49 -04:00
/*
2012-08-16 21:50:02 -03:00
* This event will be called when the failsafe changes
* boolean failsafe reflects the current state
*/
2015-05-29 23:12:49 -03:00
void Copter : : failsafe_radio_on_event ( )
2011-02-17 03:28:49 -04:00
{
2012-11-13 10:43:54 -04:00
// if motors are not armed there is nothing to do
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) ) {
2012-11-13 10:43:54 -04:00
return ;
}
2016-01-11 18:19:49 -04:00
if ( should_disarm_on_failsafe ( ) ) {
init_disarm_motors ( ) ;
} else {
if ( control_mode = = AUTO & & g . failsafe_throttle = = FS_THR_ENABLED_CONTINUE_MISSION ) {
// continue mission
2018-02-28 19:32:16 -04:00
} else if ( control_mode = = LAND & &
battery . has_failsafed ( ) & &
battery . get_highest_failsafe_priority ( ) < = FAILSAFE_LAND_PRIORITY ) {
// continue landing or other high priority failsafes
2016-01-11 18:19:49 -04:00
} else {
2018-01-19 09:44:02 -04:00
if ( g . failsafe_throttle = = FS_THR_ENABLED_ALWAYS_RTL ) {
2016-01-25 19:40:41 -04:00
set_mode_RTL_or_land_with_pause ( MODE_REASON_RADIO_FAILSAFE ) ;
2018-07-09 10:15:17 -03:00
} else if ( g . failsafe_throttle = = FS_THR_ENABLED_CONTINUE_MISSION ) {
set_mode_RTL_or_land_with_pause ( MODE_REASON_RADIO_FAILSAFE ) ;
2018-01-19 09:44:02 -04:00
} else if ( g . failsafe_throttle = = FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL ) {
set_mode_SmartRTL_or_RTL ( MODE_REASON_RADIO_FAILSAFE ) ;
} else if ( g . failsafe_throttle = = FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND ) {
set_mode_SmartRTL_or_land_with_pause ( MODE_REASON_RADIO_FAILSAFE ) ;
} else { // g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND
set_mode_land_with_pause ( MODE_REASON_RADIO_FAILSAFE ) ;
2012-11-11 09:11:12 -04:00
}
2016-01-11 18:19:49 -04:00
}
2012-08-16 21:50:02 -03:00
}
2012-12-29 23:08:25 -04:00
// log the error to the dataflash
2013-03-16 05:14:21 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_RADIO , ERROR_CODE_FAILSAFE_OCCURRED ) ;
2012-12-29 23:08:25 -04:00
2011-03-13 03:25:38 -03:00
}
2011-02-17 03:28:49 -04:00
2012-11-11 09:11:12 -04:00
// failsafe_off_event - respond to radio contact being regained
// we must be in AUTO, LAND or RTL modes
// or Stabilize or ACRO mode but with motors disarmed
2015-05-29 23:12:49 -03:00
void Copter : : failsafe_radio_off_event ( )
2011-03-13 03:25:38 -03:00
{
2012-12-29 23:08:25 -04:00
// no need to do anything except log the error as resolved
2012-11-11 09:11:12 -04:00
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
2013-03-16 05:14:21 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_RADIO , ERROR_CODE_FAILSAFE_RESOLVED ) ;
2011-02-17 03:28:49 -04:00
}
2018-02-28 19:32:16 -04:00
void Copter : : handle_battery_failsafe ( const char * type_str , const int8_t action )
2011-02-17 03:28:49 -04:00
{
2018-02-28 19:32:16 -04:00
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_BATT , ERROR_CODE_FAILSAFE_OCCURRED ) ;
2013-10-01 10:34:44 -03:00
2012-11-13 10:43:54 -04:00
// failsafe check
2018-02-28 19:32:16 -04:00
if ( should_disarm_on_failsafe ( ) ) {
init_disarm_motors ( ) ;
} else {
switch ( ( Failsafe_Action ) action ) {
case Failsafe_Action_None :
return ;
case Failsafe_Action_Land :
set_mode_land_with_pause ( MODE_REASON_BATTERY_FAILSAFE ) ;
break ;
case Failsafe_Action_RTL :
set_mode_RTL_or_land_with_pause ( MODE_REASON_BATTERY_FAILSAFE ) ;
break ;
case Failsafe_Action_SmartRTL :
2018-01-19 09:44:02 -04:00
set_mode_SmartRTL_or_RTL ( MODE_REASON_BATTERY_FAILSAFE ) ;
2018-02-28 19:32:16 -04:00
break ;
case Failsafe_Action_SmartRTL_Land :
2018-01-19 09:44:02 -04:00
set_mode_SmartRTL_or_land_with_pause ( MODE_REASON_BATTERY_FAILSAFE ) ;
2018-02-28 19:32:16 -04:00
break ;
case Failsafe_Action_Terminate :
# if ADVANCED_FAILSAFE == ENABLED
char battery_type_str [ 17 ] ;
snprintf ( battery_type_str , 17 , " %s battery " , type_str ) ;
2018-04-06 11:32:27 -03:00
g2 . afs . gcs_terminate ( true , battery_type_str ) ;
2018-02-28 19:32:16 -04:00
# else
init_disarm_motors ( ) ;
# endif
2012-11-13 10:43:54 -04:00
}
2012-06-04 22:31:40 -03:00
}
2011-02-17 03:28:49 -04:00
}
2013-04-29 09:30:22 -03:00
// failsafe_gcs_check - check for ground station failsafe
2015-05-29 23:12:49 -03:00
void Copter : : failsafe_gcs_check ( )
2013-04-29 09:30:22 -03:00
{
uint32_t last_gcs_update_ms ;
2014-12-31 21:11:28 -04:00
// return immediately if gcs failsafe is disabled, gcs has never been connected or we are not overriding rc controls from the gcs and we are not in guided mode
// this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state.
2015-01-02 13:46:41 -04:00
if ( ( ! failsafe . gcs ) & & ( g . failsafe_gcs = = FS_GCS_DISABLED | | failsafe . last_heartbeat_ms = = 0 | | ( ! failsafe . rc_override_active & & control_mode ! = GUIDED ) ) ) {
2013-04-29 09:30:22 -03:00
return ;
}
2013-07-20 08:44:56 -03:00
// calc time since last gcs update
2015-01-02 13:46:41 -04:00
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
2013-09-26 05:54:33 -03:00
last_gcs_update_ms = millis ( ) - failsafe . last_heartbeat_ms ;
2013-04-29 09:30:22 -03:00
// check if all is well
2015-01-02 13:46:41 -04:00
if ( last_gcs_update_ms < FS_GCS_TIMEOUT_MS ) {
2013-07-20 08:44:56 -03:00
// check for recovery from gcs failsafe
2013-09-26 05:54:33 -03:00
if ( failsafe . gcs ) {
2013-04-29 09:30:22 -03:00
failsafe_gcs_off_event ( ) ;
set_failsafe_gcs ( false ) ;
}
return ;
}
2013-07-20 08:44:56 -03:00
// do nothing if gcs failsafe already triggered or motors disarmed
2017-01-09 03:31:26 -04:00
if ( failsafe . gcs | | ! motors - > armed ( ) ) {
2013-04-29 09:30:22 -03:00
return ;
}
2016-05-12 14:24:23 -03:00
// GCS failsafe event has occurred
2013-04-29 09:30:22 -03:00
// update state, log to dataflash
set_failsafe_gcs ( true ) ;
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_GCS , ERROR_CODE_FAILSAFE_OCCURRED ) ;
2014-04-09 12:30:26 -03:00
// clear overrides so that RC control can be regained with radio.
2018-04-03 23:17:43 -03:00
RC_Channels : : clear_overrides ( ) ;
2014-04-09 12:30:26 -03:00
failsafe . rc_override_active = false ;
2016-01-25 19:18:38 -04:00
if ( should_disarm_on_failsafe ( ) ) {
init_disarm_motors ( ) ;
} else {
if ( control_mode = = AUTO & & g . failsafe_gcs = = FS_GCS_ENABLED_CONTINUE_MISSION ) {
// continue mission
2018-01-19 09:44:02 -04:00
} else if ( g . failsafe_gcs = = FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL ) {
set_mode_SmartRTL_or_RTL ( MODE_REASON_GCS_FAILSAFE ) ;
} else if ( g . failsafe_gcs = = FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND ) {
set_mode_SmartRTL_or_land_with_pause ( MODE_REASON_GCS_FAILSAFE ) ;
} else { // g.failsafe_gcs == FS_GCS_ENABLED_ALWAYS_RTL
2016-01-25 19:40:41 -04:00
set_mode_RTL_or_land_with_pause ( MODE_REASON_GCS_FAILSAFE ) ;
2016-01-25 19:18:38 -04:00
}
2013-04-29 09:30:22 -03:00
}
}
2013-07-20 08:44:56 -03:00
// failsafe_gcs_off_event - actions to take when GCS contact is restored
2015-05-29 23:12:49 -03:00
void Copter : : failsafe_gcs_off_event ( void )
2013-04-29 09:30:22 -03:00
{
2013-07-20 08:44:56 -03:00
// log recovery of GCS in logs?
2013-04-29 09:30:22 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_GCS , ERROR_CODE_FAILSAFE_RESOLVED ) ;
}
2016-04-22 08:37:48 -03:00
// executes terrain failsafe if data is missing for longer than a few seconds
// missing_data should be set to true if the vehicle failed to navigate because of missing data, false if navigation is proceeding successfully
void Copter : : failsafe_terrain_check ( )
{
// trigger with 5 seconds of failures while in AUTO mode
2016-08-01 05:44:12 -03:00
bool valid_mode = ( control_mode = = AUTO | | control_mode = = GUIDED | | control_mode = = GUIDED_NOGPS | | control_mode = = RTL ) ;
2016-04-22 08:37:48 -03:00
bool timeout = ( failsafe . terrain_last_failure_ms - failsafe . terrain_first_failure_ms ) > FS_TERRAIN_TIMEOUT_MS ;
bool trigger_event = valid_mode & & timeout ;
// check for clearing of event
if ( trigger_event ! = failsafe . terrain ) {
if ( trigger_event ) {
failsafe_terrain_on_event ( ) ;
} else {
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_TERRAIN , ERROR_CODE_ERROR_RESOLVED ) ;
failsafe . terrain = false ;
}
}
}
// set terrain data status (found or not found)
void Copter : : failsafe_terrain_set_status ( bool data_ok )
{
uint32_t now = millis ( ) ;
// record time of first and latest failures (i.e. duration of failures)
if ( ! data_ok ) {
failsafe . terrain_last_failure_ms = now ;
if ( failsafe . terrain_first_failure_ms = = 0 ) {
failsafe . terrain_first_failure_ms = now ;
}
} else {
// failures cleared after 0.1 seconds of persistent successes
if ( now - failsafe . terrain_last_failure_ms > 100 ) {
failsafe . terrain_last_failure_ms = 0 ;
failsafe . terrain_first_failure_ms = 0 ;
}
}
}
// terrain failsafe action
void Copter : : failsafe_terrain_on_event ( )
{
failsafe . terrain = true ;
2017-07-08 21:56:49 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Failsafe: Terrain data missing " ) ;
2016-04-22 08:37:48 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_FAILSAFE_TERRAIN , ERROR_CODE_FAILSAFE_OCCURRED ) ;
if ( should_disarm_on_failsafe ( ) ) {
init_disarm_motors ( ) ;
2018-02-23 01:33:49 -04:00
# if MODE_RTL_ENABLED == ENABLED
2016-04-22 08:37:48 -03:00
} else if ( control_mode = = RTL ) {
2017-12-11 01:43:27 -04:00
mode_rtl . restart_without_terrain ( ) ;
2018-02-23 01:33:49 -04:00
# endif
2016-04-22 08:37:48 -03:00
} else {
set_mode_RTL_or_land_with_pause ( MODE_REASON_TERRAIN_FAILSAFE ) ;
}
}
2017-07-25 08:41:18 -03:00
// check for gps glitch failsafe
void Copter : : gpsglitch_check ( )
{
// get filter status
nav_filter_status filt_status = inertial_nav . get_filter_status ( ) ;
bool gps_glitching = filt_status . flags . gps_glitching ;
// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS
if ( ap . gps_glitching ! = gps_glitching ) {
ap . gps_glitching = gps_glitching ;
if ( gps_glitching ) {
Log_Write_Error ( ERROR_SUBSYSTEM_GPS , ERROR_CODE_GPS_GLITCH ) ;
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " GPS Glitch " ) ;
} else {
Log_Write_Error ( ERROR_SUBSYSTEM_GPS , ERROR_CODE_ERROR_RESOLVED ) ;
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " GPS Glitch cleared " ) ;
}
}
}
2014-12-14 23:48:54 -04:00
// set_mode_RTL_or_land_with_pause - sets mode to RTL if possible or LAND with 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
2016-01-25 19:40:41 -04:00
void Copter : : set_mode_RTL_or_land_with_pause ( mode_reason_t reason )
2014-12-14 23:48:54 -04:00
{
// attempt to switch to RTL, if this fails then switch to Land
2016-01-25 19:40:41 -04:00
if ( ! set_mode ( RTL , reason ) ) {
2014-12-14 23:48:54 -04:00
// set mode to land will trigger mode change notification to pilot
2016-01-25 19:40:41 -04:00
set_mode_land_with_pause ( reason ) ;
2014-12-14 23:48:54 -04:00
} else {
// alert pilot to mode change
AP_Notify : : events . failsafe_mode_change = 1 ;
}
}
2018-01-19 09:44:02 -04:00
// set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
void Copter : : set_mode_SmartRTL_or_land_with_pause ( mode_reason_t reason )
{
// attempt to switch to SMART_RTL, if this failed then switch to Land
if ( ! set_mode ( SMART_RTL , reason ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " SmartRTL Unavailable, Using Land Mode " ) ;
set_mode_land_with_pause ( reason ) ;
} else {
AP_Notify : : events . failsafe_mode_change = 1 ;
}
}
// set_mode_SmartRTL_or_RTL - sets mode to SMART_RTL if possible or RTL if possible or LAND with 4 second delay before descent starts
// this is always called from a failsafe so we trigger notification to pilot
void Copter : : set_mode_SmartRTL_or_RTL ( mode_reason_t reason )
{
// attempt to switch to SmartRTL, if this failed then attempt to RTL
// if that fails, then land
if ( ! set_mode ( SMART_RTL , reason ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " SmartRTL Unavailable, Trying RTL Mode " ) ;
set_mode_RTL_or_land_with_pause ( reason ) ;
} else {
AP_Notify : : events . failsafe_mode_change = 1 ;
}
}
2016-01-11 18:19:49 -04:00
bool Copter : : should_disarm_on_failsafe ( ) {
2016-01-21 22:59:47 -04:00
if ( ap . in_arming_delay ) {
return true ;
}
2016-01-11 18:19:49 -04:00
switch ( control_mode ) {
case STABILIZE :
case ACRO :
// if throttle is zero OR vehicle is landed disarm motors
return ap . throttle_zero | | ap . land_complete ;
case AUTO :
// if mission has not started AND vehicle is landed, disarm motors
return ! ap . auto_armed & & ap . land_complete ;
default :
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold
// if landed disarm
return ap . land_complete ;
}
}
2015-05-29 23:12:49 -03:00
void Copter : : update_events ( )
2011-02-17 03:28:49 -04:00
{
2014-01-20 01:05:31 -04:00
ServoRelayEvents . update_events ( ) ;
2011-02-17 03:28:49 -04:00
}