APM:Copter
failsafe.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 //
4 // failsafe support
5 // Andrew Tridgell, December 2011
6 //
7 // our failsafe strategy is to detect main loop lockup and disarm the motors
8 //
9 
10 static bool failsafe_enabled = false;
11 static uint16_t failsafe_last_ticks;
12 static uint32_t failsafe_last_timestamp;
13 static bool in_failsafe;
14 
15 //
16 // failsafe_enable - enable failsafe
17 //
19 {
20  failsafe_enabled = true;
22 }
23 
24 //
25 // failsafe_disable - used when we know we are going to delay the mainloop significantly
26 //
28 {
29  failsafe_enabled = false;
30 }
31 
32 //
33 // failsafe_check - this function is called from the core timer interrupt at 1kHz.
34 //
36 {
37  uint32_t tnow = AP_HAL::micros();
38 
39  const uint16_t ticks = scheduler.ticks();
40  if (ticks != failsafe_last_ticks) {
41  // the main loop is running, all is OK
42  failsafe_last_ticks = ticks;
44  if (in_failsafe) {
45  in_failsafe = false;
47  }
48  return;
49  }
50 
51  if (!in_failsafe && failsafe_enabled && tnow - failsafe_last_timestamp > 2000000) {
52  // motors are running but we have gone 2 second since the
53  // main loop ran. That means we're in trouble and should
54  // disarm the motors->
55  in_failsafe = true;
56  // reduce motors to minimum (we do not immediately disarm because we want to log the failure)
57  if (motors->armed()) {
58  motors->output_min();
59  }
60  // log an error
62  }
63 
64  if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) {
65  // disarm motors every second
67  if(motors->armed()) {
68  motors->armed(false);
69  motors->output();
70  }
71  }
72 }
73 
74 
75 #if ADVANCED_FAILSAFE == ENABLED
76 /*
77  check for AFS failsafe check
78 */
79 void Copter::afs_fs_check(void)
80 {
81  // perform AFS failsafe checks
82 #if AC_FENCE
83  const bool fence_breached = fence.get_breaches() != 0;
84 #else
85  const bool fence_breached = false;
86 #endif
87  g2.afs.check(failsafe.last_heartbeat_ms, fence_breached, last_radio_update_ms);
88 }
89 #endif
uint16_t ticks() const
AC_Fence fence
Definition: Copter.h:527
#define ERROR_CODE_FAILSAFE_RESOLVED
Definition: defines.h:424
#define ERROR_CODE_FAILSAFE_OCCURRED
Definition: defines.h:425
void failsafe_disable()
Definition: failsafe.cpp:27
static uint32_t failsafe_last_timestamp
Definition: failsafe.cpp:12
uint8_t get_breaches() const
uint32_t last_radio_update_ms
Definition: Copter.h:583
static uint16_t failsafe_last_ticks
Definition: failsafe.cpp:11
MOTOR_CLASS * motors
Definition: Copter.h:422
static bool failsafe_enabled
Definition: failsafe.cpp:10
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
#define ERROR_SUBSYSTEM_CPU
Definition: defines.h:411
AP_AdvancedFailsafe_Copter afs
Definition: Parameters.h:547
AP_Scheduler scheduler
Definition: Copter.h:212
static bool in_failsafe
Definition: failsafe.cpp:13
void check(uint32_t last_heartbeat_ms, bool geofence_breached, uint32_t last_valid_rc_ms)
struct Copter::@2 failsafe
ParametersG2 g2
Definition: Copter.h:209
uint32_t micros()
void failsafe_check()
Definition: failsafe.cpp:35
void failsafe_enable()
Definition: failsafe.cpp:18