75 #if ADVANCED_FAILSAFE == ENABLED 76 char battery_type_str[17];
77 snprintf(battery_type_str, 17,
"%s battery", type_str);
89 uint32_t last_gcs_update_ms;
123 failsafe.rc_override_active =
false;
154 bool trigger_event = valid_mode &&
timeout;
157 if (trigger_event !=
failsafe.terrain) {
174 failsafe.terrain_last_failure_ms = now;
175 if (
failsafe.terrain_first_failure_ms == 0) {
176 failsafe.terrain_first_failure_ms = now;
180 if (now -
failsafe.terrain_last_failure_ms > 100) {
181 failsafe.terrain_last_failure_ms = 0;
182 failsafe.terrain_first_failure_ms = 0;
191 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Failsafe: Terrain data missing");
196 #if MODE_RTL_ENABLED == ENABLED 213 if (
ap.gps_glitching != gps_glitching) {
214 ap.gps_glitching = gps_glitching;
220 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"GPS Glitch cleared");
245 gcs().
send_text(MAV_SEVERITY_WARNING,
"SmartRTL Unavailable, Using Land Mode");
259 gcs().
send_text(MAV_SEVERITY_WARNING,
"SmartRTL Unavailable, Trying RTL Mode");
267 if (
ap.in_arming_delay) {
275 return ap.throttle_zero ||
ap.land_complete;
278 return !
ap.auto_armed &&
ap.land_complete;
282 return ap.land_complete;
void set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason)
void failsafe_radio_off_event()
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND
#define ERROR_CODE_FAILSAFE_RESOLVED
bool gcs_terminate(bool should_terminate, const char *reason)
#define ERROR_CODE_FAILSAFE_OCCURRED
#define FS_THR_ENABLED_CONTINUE_MISSION
uint32_t failsafe_mode_change
void set_mode_RTL_or_land_with_pause(mode_reason_t reason)
void set_mode_land_with_pause(mode_reason_t reason)
int8_t get_highest_failsafe_priority(void) const
AP_InertialNav_NavEKF inertial_nav
#define ERROR_SUBSYSTEM_FAILSAFE_BATT
void failsafe_terrain_on_event()
#define ERROR_SUBSYSTEM_FAILSAFE_GCS
void set_mode_SmartRTL_or_RTL(mode_reason_t reason)
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
#define ERROR_SUBSYSTEM_GPS
nav_filter_status get_filter_status() const
#define ERROR_CODE_GPS_GLITCH
#define ERROR_SUBSYSTEM_FAILSAFE_RADIO
void failsafe_gcs_check()
#define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN
AP_AdvancedFailsafe_Copter afs
void failsafe_radio_on_event()
bool set_mode(control_mode_t mode, mode_reason_t reason)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void failsafe_terrain_check()
#define FS_TERRAIN_TIMEOUT_MS
void handle_battery_failsafe(const char *type_str, const int8_t action)
#define FS_THR_ENABLED_ALWAYS_RTL
struct nav_filter_status::@138 flags
AP_ServoRelayEvents ServoRelayEvents
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL
void failsafe_terrain_set_status(bool data_ok)
struct Copter::@2 failsafe
void init_disarm_motors()
int snprintf(char *str, size_t size, const char *fmt,...)
static void clear_overrides(void)
#define ERROR_CODE_ERROR_RESOLVED
void set_failsafe_gcs(bool b)
AP_Int8 failsafe_throttle
#define FS_GCS_ENABLED_CONTINUE_MISSION
static struct notify_events_type events
#define FS_GCS_TIMEOUT_MS
control_mode_t control_mode
bool has_failsafed(void) const
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND
bool should_disarm_on_failsafe()
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL
void failsafe_gcs_off_event(void)
void restart_without_terrain()
#define FAILSAFE_LAND_PRIORITY