APM:Copter
crash_check.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // Code to detect a crash main ArduCopter code
4 #define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
5 #define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond angle max is signal we are inverted
6 #define CRASH_CHECK_ACCEL_MAX 3.0f // vehicle must be accelerating less than 3m/s/s to be considered crashed
7 
8 // crash_check - disarms motors if a crash has been detected
9 // crashes are detected by the vehicle being more than 20 degrees beyond it's angle limits continuously for more than 1 second
10 // called at MAIN_LOOP_RATE
12 {
13  static uint16_t crash_counter; // number of iterations vehicle may have been crashed
14 
15  // return immediately if disarmed, or crash checking disabled
16  if (!motors->armed() || ap.land_complete || g.fs_crash_check == 0) {
17  crash_counter = 0;
18  return;
19  }
20 
21  // return immediately if we are not in an angle stabilize flight mode or we are flipping
22  if (control_mode == ACRO || control_mode == FLIP) {
23  crash_counter = 0;
24  return;
25  }
26 
27  // vehicle not crashed if 1hz filtered acceleration is more than 3m/s (1G on Z-axis has been subtracted)
29  crash_counter = 0;
30  return;
31  }
32 
33  // check for angle error over 30 degrees
34  const float angle_error = attitude_control->get_att_error_angle_deg();
35  if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
36  crash_counter = 0;
37  return;
38  }
39 
40  // we may be crashing
41  crash_counter++;
42 
43  // check if crashing for 2 seconds
44  if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
45  // log an error in the dataflash
47  // send message to gcs
48  gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming");
49  // disarm motors
51  }
52 }
53 
54 #if PARACHUTE == ENABLED
55 
56 // Code to detect a crash main ArduCopter code
57 #define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute
58 #define PARACHUTE_CHECK_ANGLE_DEVIATION_CD 3000 // 30 degrees off from target indicates a loss of control
59 
60 // parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected
61 // vehicle is considered to have a "serious loss of control" by the vehicle being more than 30 degrees off from the target roll and pitch angles continuously for 1 second
62 // called at MAIN_LOOP_RATE
64 {
65  static uint16_t control_loss_count; // number of iterations we have been out of control
66  static int32_t baro_alt_start;
67 
68  // exit immediately if parachute is not enabled
69  if (!parachute.enabled()) {
70  return;
71  }
72 
73  // call update to give parachute a chance to move servo or relay back to off position
74  parachute.update();
75 
76  // return immediately if motors are not armed or pilot's throttle is above zero
77  if (!motors->armed()) {
78  control_loss_count = 0;
79  return;
80  }
81 
82  // return immediately if we are not in an angle stabilize flight mode or we are flipping
83  if (control_mode == ACRO || control_mode == FLIP) {
84  control_loss_count = 0;
85  return;
86  }
87 
88  // ensure we are flying
89  if (ap.land_complete) {
90  control_loss_count = 0;
91  return;
92  }
93 
94  // ensure the first control_loss event is from above the min altitude
95  if (control_loss_count == 0 && parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100)) {
96  return;
97  }
98 
99  // check for angle error over 30 degrees
100  const float angle_error = attitude_control->get_att_error_angle_deg();
101  if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
102  if (control_loss_count > 0) {
103  control_loss_count--;
104  }
105  return;
106  }
107 
108  // increment counter
109  if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
110  control_loss_count++;
111  }
112 
113  // record baro alt if we have just started losing control
114  if (control_loss_count == 1) {
115  baro_alt_start = baro_alt;
116 
117  // exit if baro altitude change indicates we are not falling
118  } else if (baro_alt >= baro_alt_start) {
119  control_loss_count = 0;
120  return;
121 
122  // To-Do: add check that the vehicle is actually falling
123 
124  // check if loss of control for at least 1 second
125  } else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
126  // reset control loss counter
127  control_loss_count = 0;
128  // log an error in the dataflash
130  // release parachute
132  }
133 }
134 
135 // parachute_release - trigger the release of the parachute, disarm the motors and notify the user
137 {
138  // send message to gcs and dataflash
139  gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Released");
141 
142  // disarm motors
144 
145  // release parachute
146  parachute.release();
147 
148  // deploy landing gear
150 }
151 
152 // parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error
153 // checks if the vehicle is landed
155 {
156  // exit immediately if parachute is not enabled
157  if (!parachute.enabled()) {
158  return;
159  }
160 
161  // do not release if vehicle is landed
162  // do not release if we are landed or below the minimum altitude above home
163  if (ap.land_complete) {
164  // warn user of reason for failure
165  gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed");
166  // log an error in the dataflash
168  return;
169  }
170 
171  // do not release if we are landed or below the minimum altitude above home
172  if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {
173  // warn user of reason for failure
174  gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");
175  // log an error in the dataflash
177  return;
178  }
179 
180  // if we get this far release parachute
182 }
183 
184 #endif // PARACHUTE == ENABLED
#define ERROR_CODE_PARACHUTE_TOO_LOW
Definition: defines.h:444
int32_t baro_alt
Definition: Copter.h:466
#define DATA_PARACHUTE_RELEASED
Definition: defines.h:371
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
void crash_check()
Definition: crash_check.cpp:11
LowPassFilterVector3f land_accel_ef_filter
Definition: Copter.h:468
uint16_t get_loop_rate_hz(void)
#define CRASH_CHECK_ACCEL_MAX
Definition: crash_check.cpp:6
#define ERROR_SUBSYSTEM_PARACHUTE
Definition: defines.h:407
void parachute_manual_release()
GCS_Copter & gcs()
Definition: Copter.h:301
AP_Int8 fs_crash_check
Definition: Parameters.h:454
void parachute_check()
Definition: crash_check.cpp:63
#define ERROR_CODE_PARACHUTE_LANDED
Definition: defines.h:445
MOTOR_CLASS * motors
Definition: Copter.h:422
AP_LandingGear landinggear
Definition: Copter.h:557
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
void enabled(bool on_off)
Definition: defines.h:93
int32_t alt
Definition: defines.h:103
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
Location_Class current_loc
Definition: Copter.h:475
AP_Parachute parachute
Definition: Copter.h:553
void send_text(MAV_SEVERITY severity, const char *fmt,...)
const Vector3f & get() const
float length(void) const
AP_Scheduler scheduler
Definition: Copter.h:212
Parameters g
Definition: Copter.h:208
#define CRASH_CHECK_ANGLE_DEVIATION_DEG
Definition: crash_check.cpp:5
void release()
void init_disarm_motors()
Definition: motors.cpp:241
void set_position(LandingGearCommand cmd)
#define ERROR_CODE_CRASH_CHECK_CRASH
Definition: defines.h:431
void parachute_release()
#define ERROR_CODE_CRASH_CHECK_LOSS_OF_CONTROL
Definition: defines.h:432
#define PARACHUTE_CHECK_TRIGGER_SEC
Definition: crash_check.cpp:57
int16_t alt_min() const
control_mode_t control_mode
Definition: Copter.h:345
#define CRASH_CHECK_TRIGGER_SEC
Definition: crash_check.cpp:4
#define ERROR_SUBSYSTEM_CRASH_CHECK
Definition: defines.h:404