APM:Copter
events.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * This event will be called when the failsafe changes
5  * boolean failsafe reflects the current state
6  */
8 {
9  // if motors are not armed there is nothing to do
10  if( !motors->armed() ) {
11  return;
12  }
13 
16  } else {
18  // continue mission
19  } else if (control_mode == LAND &&
22  // continue landing or other high priority failsafes
23  } else {
30  } else { // g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND
32  }
33  }
34  }
35 
36  // log the error to the dataflash
38 
39 }
40 
41 // failsafe_off_event - respond to radio contact being regained
42 // we must be in AUTO, LAND or RTL modes
43 // or Stabilize or ACRO mode but with motors disarmed
45 {
46  // no need to do anything except log the error as resolved
47  // user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
49 }
50 
51 void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
52 {
54 
55  // failsafe check
58  } else {
59  switch ((Failsafe_Action)action) {
61  return;
64  break;
67  break;
70  break;
73  break;
75 #if ADVANCED_FAILSAFE == ENABLED
76  char battery_type_str[17];
77  snprintf(battery_type_str, 17, "%s battery", type_str);
78  g2.afs.gcs_terminate(true, battery_type_str);
79 #else
81 #endif
82  }
83  }
84 }
85 
86 // failsafe_gcs_check - check for ground station failsafe
88 {
89  uint32_t last_gcs_update_ms;
90 
91  // 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
92  // 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.
93  if ((!failsafe.gcs)&&(g.failsafe_gcs == FS_GCS_DISABLED || failsafe.last_heartbeat_ms == 0 || (!failsafe.rc_override_active && control_mode != GUIDED))) {
94  return;
95  }
96 
97  // calc time since last gcs update
98  // note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
99  last_gcs_update_ms = millis() - failsafe.last_heartbeat_ms;
100 
101  // check if all is well
102  if (last_gcs_update_ms < FS_GCS_TIMEOUT_MS) {
103  // check for recovery from gcs failsafe
104  if (failsafe.gcs) {
106  set_failsafe_gcs(false);
107  }
108  return;
109  }
110 
111  // do nothing if gcs failsafe already triggered or motors disarmed
112  if (failsafe.gcs || !motors->armed()) {
113  return;
114  }
115 
116  // GCS failsafe event has occurred
117  // update state, log to dataflash
118  set_failsafe_gcs(true);
120 
121  // clear overrides so that RC control can be regained with radio.
123  failsafe.rc_override_active = false;
124 
127  } else {
129  // continue mission
134  } else { // g.failsafe_gcs == FS_GCS_ENABLED_ALWAYS_RTL
136  }
137  }
138 }
139 
140 // failsafe_gcs_off_event - actions to take when GCS contact is restored
142 {
143  // log recovery of GCS in logs?
145 }
146 
147 // executes terrain failsafe if data is missing for longer than a few seconds
148 // missing_data should be set to true if the vehicle failed to navigate because of missing data, false if navigation is proceeding successfully
150 {
151  // trigger with 5 seconds of failures while in AUTO mode
152  bool valid_mode = (control_mode == AUTO || control_mode == GUIDED || control_mode == GUIDED_NOGPS || control_mode == RTL);
153  bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
154  bool trigger_event = valid_mode && timeout;
155 
156  // check for clearing of event
157  if (trigger_event != failsafe.terrain) {
158  if (trigger_event) {
160  } else {
162  failsafe.terrain = false;
163  }
164  }
165 }
166 
167 // set terrain data status (found or not found)
169 {
170  uint32_t now = millis();
171 
172  // record time of first and latest failures (i.e. duration of failures)
173  if (!data_ok) {
174  failsafe.terrain_last_failure_ms = now;
175  if (failsafe.terrain_first_failure_ms == 0) {
176  failsafe.terrain_first_failure_ms = now;
177  }
178  } else {
179  // failures cleared after 0.1 seconds of persistent successes
180  if (now - failsafe.terrain_last_failure_ms > 100) {
181  failsafe.terrain_last_failure_ms = 0;
182  failsafe.terrain_first_failure_ms = 0;
183  }
184  }
185 }
186 
187 // terrain failsafe action
189 {
190  failsafe.terrain = true;
191  gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing");
193 
196 #if MODE_RTL_ENABLED == ENABLED
197  } else if (control_mode == RTL) {
199 #endif
200  } else {
202  }
203 }
204 
205 // check for gps glitch failsafe
207 {
208  // get filter status
210  bool gps_glitching = filt_status.flags.gps_glitching;
211 
212  // log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS
213  if (ap.gps_glitching != gps_glitching) {
214  ap.gps_glitching = gps_glitching;
215  if (gps_glitching) {
217  gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch");
218  } else {
220  gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");
221  }
222  }
223 }
224 
225 // set_mode_RTL_or_land_with_pause - sets mode to RTL if possible or LAND with 4 second delay before descent starts
226 // this is always called from a failsafe so we trigger notification to pilot
228 {
229  // attempt to switch to RTL, if this fails then switch to Land
230  if (!set_mode(RTL, reason)) {
231  // set mode to land will trigger mode change notification to pilot
232  set_mode_land_with_pause(reason);
233  } else {
234  // alert pilot to mode change
236  }
237 }
238 
239 // set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts
240 // this is always called from a failsafe so we trigger notification to pilot
242 {
243  // attempt to switch to SMART_RTL, if this failed then switch to Land
244  if (!set_mode(SMART_RTL, reason)) {
245  gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
246  set_mode_land_with_pause(reason);
247  } else {
249  }
250 }
251 
252 // 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
253 // this is always called from a failsafe so we trigger notification to pilot
255 {
256  // attempt to switch to SmartRTL, if this failed then attempt to RTL
257  // if that fails, then land
258  if (!set_mode(SMART_RTL, reason)) {
259  gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
261  } else {
263  }
264 }
265 
267  if (ap.in_arming_delay) {
268  return true;
269  }
270 
271  switch(control_mode) {
272  case STABILIZE:
273  case ACRO:
274  // if throttle is zero OR vehicle is landed disarm motors
275  return ap.throttle_zero || ap.land_complete;
276  case AUTO:
277  // if mission has not started AND vehicle is landed, disarm motors
278  return !ap.auto_armed && ap.land_complete;
279  default:
280  // used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold
281  // if landed disarm
282  return ap.land_complete;
283  }
284 }
285 
287 {
289 }
290 
void set_mode_SmartRTL_or_land_with_pause(mode_reason_t reason)
Definition: events.cpp:241
void failsafe_radio_off_event()
Definition: events.cpp:44
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND
Definition: defines.h:460
uint32_t timeout
#define ERROR_CODE_FAILSAFE_RESOLVED
Definition: defines.h:424
bool gcs_terminate(bool should_terminate, const char *reason)
#define ERROR_CODE_FAILSAFE_OCCURRED
Definition: defines.h:425
#define FS_THR_ENABLED_CONTINUE_MISSION
Definition: defines.h:457
void set_mode_RTL_or_land_with_pause(mode_reason_t reason)
Definition: events.cpp:227
Definition: defines.h:95
GCS_Copter & gcs()
Definition: Copter.h:301
void set_mode_land_with_pause(mode_reason_t reason)
Definition: mode_land.cpp:152
Definition: defines.h:96
Definition: defines.h:100
int8_t get_highest_failsafe_priority(void) const
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
mode_reason_t
Definition: defines.h:115
MOTOR_CLASS * motors
Definition: Copter.h:422
#define ERROR_SUBSYSTEM_FAILSAFE_BATT
Definition: defines.h:398
#define FS_GCS_DISABLED
Definition: defines.h:463
void failsafe_terrain_on_event()
Definition: events.cpp:188
AP_Int8 failsafe_gcs
Definition: Parameters.h:398
#define ERROR_SUBSYSTEM_FAILSAFE_GCS
Definition: defines.h:400
void gpsglitch_check()
Definition: events.cpp:206
void set_mode_SmartRTL_or_RTL(mode_reason_t reason)
Definition: events.cpp:254
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
#define ERROR_SUBSYSTEM_GPS
Definition: defines.h:403
nav_filter_status get_filter_status() const
Definition: defines.h:93
AP_BattMonitor battery
Definition: Copter.h:445
#define ERROR_CODE_GPS_GLITCH
Definition: defines.h:452
uint32_t millis()
#define ERROR_SUBSYSTEM_FAILSAFE_RADIO
Definition: defines.h:397
void failsafe_gcs_check()
Definition: events.cpp:87
ModeRTL mode_rtl
Definition: Copter.h:994
#define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN
Definition: defines.h:415
AP_AdvancedFailsafe_Copter afs
Definition: Parameters.h:547
void failsafe_radio_on_event()
Definition: events.cpp:7
bool set_mode(control_mode_t mode, mode_reason_t reason)
Definition: mode.cpp:171
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void update_events()
Definition: events.cpp:286
void failsafe_terrain_check()
Definition: events.cpp:149
#define FS_TERRAIN_TIMEOUT_MS
Definition: config.h:167
void handle_battery_failsafe(const char *type_str, const int8_t action)
Definition: events.cpp:51
#define FS_THR_ENABLED_ALWAYS_RTL
Definition: defines.h:456
struct nav_filter_status::@138 flags
Parameters g
Definition: Copter.h:208
AP_ServoRelayEvents ServoRelayEvents
Definition: Copter.h:512
#define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL
Definition: defines.h:459
void failsafe_terrain_set_status(bool data_ok)
Definition: events.cpp:168
void update_events(void)
struct Copter::@2 failsafe
void init_disarm_motors()
Definition: motors.cpp:241
int snprintf(char *str, size_t size, const char *fmt,...)
static void clear_overrides(void)
#define ERROR_CODE_ERROR_RESOLVED
Definition: defines.h:418
void set_failsafe_gcs(bool b)
Definition: AP_State.cpp:74
ParametersG2 g2
Definition: Copter.h:209
AP_Int8 failsafe_throttle
Definition: Parameters.h:421
#define FS_GCS_ENABLED_CONTINUE_MISSION
Definition: defines.h:465
static struct notify_events_type events
#define FS_GCS_TIMEOUT_MS
Definition: config.h:152
control_mode_t control_mode
Definition: Copter.h:345
bool has_failsafed(void) const
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND
Definition: defines.h:467
bool should_disarm_on_failsafe()
Definition: events.cpp:266
Failsafe_Action
Definition: Copter.h:629
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL
Definition: defines.h:466
void failsafe_gcs_off_event(void)
Definition: events.cpp:141
Definition: defines.h:98
void restart_without_terrain()
Definition: mode_rtl.cpp:25
#define FAILSAFE_LAND_PRIORITY
Definition: Copter.h:648