APM:Libraries
AP_AdvancedFailsafe.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  AP_AdvancedFailsafe.cpp
18 
19  This is an advanced failsafe module originally modelled on the
20  failsafe rules of the Outback Challenge
21 */
22 #include <AP_HAL/AP_HAL.h>
23 #include "AP_AdvancedFailsafe.h"
24 #include <RC_Channel/RC_Channel.h>
26 #include <GCS_MAVLink/GCS.h>
27 
28 extern const AP_HAL::HAL& hal;
29 
30 // table of user settable parameters
32  // @Param: ENABLE
33  // @DisplayName: Enable Advanced Failsafe
34  // @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
35  // @User: Advanced
37 
38  // @Param: MAN_PIN
39  // @DisplayName: Manual Pin
40  // @Description: This sets a digital output pin to set high when in manual mode
41  // @User: Advanced
42  AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
43 
44  // @Param: HB_PIN
45  // @DisplayName: Heartbeat Pin
46  // @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination.
47  // @User: Advanced
48  AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
49 
50  // @Param: WP_COMMS
51  // @DisplayName: Comms Waypoint
52  // @Description: Waypoint number to navigate to on comms loss
53  // @User: Advanced
54  AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),
55 
56  // @Param: GPS_LOSS
57  // @DisplayName: GPS Loss Waypoint
58  // @Description: Waypoint number to navigate to on GPS lock loss
59  // @User: Advanced
60  AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),
61 
62  // @Param: TERMINATE
63  // @DisplayName: Force Terminate
64  // @Description: Can be set in flight to force termination of the heartbeat signal
65  // @User: Advanced
66  AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),
67 
68  // @Param: TERM_ACTION
69  // @DisplayName: Terminate action
70  // @Description: This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup APM to handle it here. Please consult the wiki for more information on the possible values of the parameter
71  // @User: Advanced
72  AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
73 
74  // @Param: TERM_PIN
75  // @DisplayName: Terminate Pin
76  // @Description: This sets a digital output pin to set high on flight termination
77  // @User: Advanced
78  AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),
79 
80  // @Param: AMSL_LIMIT
81  // @DisplayName: AMSL limit
82  // @Description: This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
83  // @User: Advanced
84  // @Units: m
85  AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),
86 
87  // @Param: AMSL_ERR_GPS
88  // @DisplayName: Error margin for GPS based AMSL limit
89  // @Description: This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
90  // @User: Advanced
91  // @Units: m
92  AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),
93 
94  // @Param: QNH_PRESSURE
95  // @DisplayName: QNH pressure
96  // @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
97  // @Units: mbar
98  // @User: Advanced
99  AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),
100 
101  // *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE
102 
103  // *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.
104 
105  // @Param: MAX_GPS_LOSS
106  // @DisplayName: Maximum number of GPS loss events
107  // @Description: Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
108  // @User: Advanced
109  AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),
110 
111  // @Param: MAX_COM_LOSS
112  // @DisplayName: Maximum number of comms loss events
113  // @Description: Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
114  // @User: Advanced
115  AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),
116 
117  // @Param: GEOFENCE
118  // @DisplayName: Enable geofence Advanced Failsafe
119  // @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
120  // @User: Advanced
121  AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),
122 
123  // @Param: RC
124  // @DisplayName: Enable RC Advanced Failsafe
125  // @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
126  // @User: Advanced
127  AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),
128 
129  // @Param: RC_MAN_ONLY
130  // @DisplayName: Enable RC Termination only in manual control modes
131  // @Description: If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
132  // @User: Advanced
133  AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),
134 
135  // @Param: DUAL_LOSS
136  // @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
137  // @Description: This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
138  // @User: Advanced
139  AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),
140 
141  // @Param: RC_FAIL_TIME
142  // @DisplayName: RC failure time
143  // @Description: This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
144  // @User: Advanced
145  // @Units: s
146  AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),
147 
149 };
150 
151 // check for Failsafe conditions. This is called at 10Hz by the main
152 // ArduPlane code
153 void
154 AP_AdvancedFailsafe::check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
155 {
156  if (!_enable) {
157  return;
158  }
159  // only set the termination capability, clearing it can mess up copter and sub which can always be terminated
160  hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION);
161 
162  // we always check for fence breach
163  if(_enable_geofence_fs) {
164  if (geofence_breached || check_altlimit()) {
165  if (!_terminate) {
166  gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");
167  _terminate.set_and_notify(1);
168  }
169  }
170  }
171 
172  enum control_mode mode = afs_mode();
173 
174  // check if RC termination is enabled
175  // check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0
177  (mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&
178  _rc_fail_time_seconds > 0 &&
179  (AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {
180  gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");
181  _terminate.set_and_notify(1);
182  }
183 
184  // tell the failsafe board if we are in manual control
185  // mode. This tells it to pass through controls from the
186  // receiver
187  if (_manual_pin != -1) {
189  hal.gpio->write(_manual_pin, mode==AFS_MANUAL);
190  }
191 
192  uint32_t now = AP_HAL::millis();
193  bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
194  bool gps_lock_ok = ((now - gps.last_fix_time_ms()) < 3000);
195 
196  switch (_state) {
197  case STATE_PREFLIGHT:
198  // we startup in preflight mode. This mode ends when
199  // we first enter auto.
200  if (mode == AFS_AUTO) {
201  gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");
202  _state = STATE_AUTO;
203  }
204  break;
205 
206  case STATE_AUTO:
207  // this is the normal mode.
208  if (!gcs_link_ok) {
209  gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");
211  if (_wp_comms_hold) {
214  }
215  // if two events happen within 30s we consider it to be part of the same event
216  if (now - _last_comms_loss_ms > 30*1000UL) {
218  _last_comms_loss_ms = now;
219  }
220  break;
221  }
222  if (!gps_lock_ok) {
223  gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");
225  if (_wp_gps_loss) {
228  }
229  // if two events happen within 30s we consider it to be part of the same event
230  if (now - _last_gps_loss_ms > 30*1000UL) {
231  _gps_loss_count++;
232  _last_gps_loss_ms = now;
233  }
234  break;
235  }
236  break;
237 
239  if (!gps_lock_ok) {
240  // losing GPS lock when data link is lost
241  // leads to termination if AFS_DUAL_LOSS is 1
242  if(_enable_dual_loss) {
243  if (!_terminate) {
244  gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
245  _terminate.set_and_notify(1);
246  }
247  }
248  } else if (gcs_link_ok) {
249  _state = STATE_AUTO;
250  gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");
251  // we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
252  if (_saved_wp != 0 &&
253  (_max_comms_loss <= 0 ||
256  _saved_wp = 0;
257  }
258  }
259  break;
260 
261  case STATE_GPS_LOSS:
262  if (!gcs_link_ok) {
263  // losing GCS link when GPS lock lost
264  // leads to termination if AFS_DUAL_LOSS is 1
265  if (!_terminate && _enable_dual_loss) {
266  gcs().send_text(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
267  _terminate.set_and_notify(1);
268  }
269  } else if (gps_lock_ok) {
270  gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");
271  _state = STATE_AUTO;
272  // we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS
273  if (_saved_wp != 0 &&
276  _saved_wp = 0;
277  }
278  }
279  break;
280  }
281 
282  // if we are not terminating or if there is a separate terminate
283  // pin configured then toggle the heartbeat pin at 10Hz
284  if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
288  }
289 
290  // set the terminate pin
291  if (_terminate_pin != -1) {
293  hal.gpio->write(_terminate_pin, _terminate?1:0);
294  }
295 }
296 
297 
298 // send heartbeat messages during sensor calibration
299 void
301 {
302  if (!_enable) {
303  return;
304  }
305 
306  // if we are not terminating or if there is a separate terminate
307  // pin configured then toggle the heartbeat pin at 10Hz
308  if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
312  }
313 }
314 
315 // check for altitude limit breach
316 bool
318 {
319  if (!_enable) {
320  return false;
321  }
322  if (_amsl_limit == 0 || _qnh_pressure <= 0) {
323  // no limit set
324  return false;
325  }
326 
327  // see if the barometer is dead
328  const AP_Baro &baro = AP::baro();
329  if (AP_HAL::millis() - baro.get_last_update() > 5000) {
330  // the barometer has been unresponsive for 5 seconds. See if we can switch to GPS
331  if (_amsl_margin_gps != -1 &&
334  // GPS based altitude OK
335  return false;
336  }
337  // no barometer - immediate termination
338  return true;
339  }
340 
341  float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());
342  if (alt_amsl > _amsl_limit) {
343  // pressure altitude breach
344  return true;
345  }
346 
347  // all OK
348  return false;
349 }
350 
351 /*
352  return true if we should crash the vehicle
353  */
355 {
356  if (!_enable) {
357  return false;
358  }
359  // ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk
360  if (!_failsafe_setup) {
361  _failsafe_setup = true;
363  }
364 
365  // determine if the vehicle should be crashed
366  // only possible if FS_TERM_ACTION is 42 and _terminate is non zero
367  // _terminate may be set via parameters, or a mavlink command
368  if (_terminate &&
371  // we are terminating
372  return true;
373  }
374 
375  // continue flying
376  return false;
377 }
378 
379 // update GCS based termination
380 // returns true if AFS is in the desired termination state
381 bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {
382  if (!_enable) {
383  gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
384  return false;
385  }
386 
387  _terminate.set_and_notify(should_terminate ? 1 : 0);
388 
389  // evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct
390  bool is_terminating = should_crash_vehicle();
391 
392  if(should_terminate == is_terminating) {
393  if (is_terminating) {
394  gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to %s", reason);
395  } else {
396  gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);
397  }
398  return true;
399  } else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
400  gcs().send_text(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");
401  }
402  return false;
403 }
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
bool gcs_terminate(bool should_terminate, const char *reason)
virtual enum control_mode afs_mode(void)=0
Interface definition for the various Ground Control System.
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_HAL::Util * util
Definition: HAL.h:115
void set_capabilities(uint64_t cap)
Definition: Util.h:17
uint32_t last_fix_time_ms(uint8_t instance) const
Definition: AP_GPS.h:301
GCS & gcs()
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
Definition: AP_Mission.h:384
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
virtual void write(uint8_t pin, uint8_t value)=0
float get_altitude_difference(float base_pressure, float pressure) const
Definition: AP_Baro.cpp:271
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
virtual void setup_IO_failsafe(void)=0
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
RC_Channel manager, with EEPROM-backed storage of constants.
#define f(i)
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
virtual void pinMode(uint8_t pin, uint8_t output)=0
bool set_current_cmd(uint16_t index)
Definition: AP_Mission.cpp:339
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
float get_pressure(void) const
Definition: AP_Baro.h:59
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
static const struct AP_Param::GroupInfo var_info[]
void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
AP_Baro & baro()
Definition: AP_Baro.cpp:737
uint32_t get_last_update(void) const
Definition: AP_Baro.h:116
#define AP_GROUPEND
Definition: AP_Param.h:121
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14