forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
failsafe.cpp
155 lines (142 loc) · 4.9 KB
/
failsafe.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
/*
failsafe support
Andrew Tridgell, December 2011
*/
#include "Rover.h"
#include <stdio.h>
/*
our failsafe strategy is to detect main loop lockup and switch to
passing inputs straight from the RC inputs to RC outputs.
*/
/*
this failsafe_check function is called from the core timer interrupt
at 1kHz.
*/
void Rover::failsafe_check()
{
static uint16_t last_ticks;
static uint32_t last_timestamp;
const uint32_t tnow = AP_HAL::micros();
const uint16_t ticks = scheduler.ticks();
if (ticks != last_ticks) {
// the main loop is running, all is OK
last_ticks = ticks;
last_timestamp = tnow;
return;
}
if (tnow - last_timestamp > 200000) {
// we have gone at least 0.2 seconds since the main loop
// ran. That means we're in trouble, or perhaps are in
// an initialisation routine or log erase. disarm the motors
// To-Do: log error
if (arming.is_armed()) {
// disarm motors
arming.disarm();
}
}
}
/*
called to set/unset a failsafe event.
*/
void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
{
uint8_t old_bits = failsafe.bits;
if (on) {
failsafe.bits |= failsafe_type;
} else {
failsafe.bits &= ~failsafe_type;
}
if (old_bits == 0 && failsafe.bits != 0) {
// a failsafe event has started
failsafe.start_time = millis();
}
if (failsafe.triggered != 0 && failsafe.bits == 0) {
// a failsafe event has ended
gcs().send_text(MAV_SEVERITY_INFO, "Failsafe ended");
}
failsafe.triggered &= failsafe.bits;
if ((failsafe.triggered == 0) &&
(failsafe.bits != 0) &&
(millis() - failsafe.start_time > g.fs_timeout * 1000) &&
(control_mode != &mode_rtl) &&
((control_mode != &mode_hold || (g2.fs_options & (uint32_t)Failsafe_Options::Failsafe_Option_Active_In_Hold)))) {
failsafe.triggered = failsafe.bits;
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe trigger 0x%x", (unsigned int)failsafe.triggered);
// clear rc overrides
RC_Channels::clear_overrides();
if ((control_mode == &mode_auto) &&
((failsafe_type == FAILSAFE_EVENT_THROTTLE && g.fs_throttle_enabled == FS_THR_ENABLED_CONTINUE_MISSION) ||
(failsafe_type == FAILSAFE_EVENT_GCS && g.fs_gcs_enabled == FS_GCS_ENABLED_CONTINUE_MISSION))) {
// continue with mission in auto mode
} else {
switch (g.fs_action) {
case Failsafe_Action_None:
break;
case Failsafe_Action_RTL:
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
set_mode(mode_hold, MODE_REASON_FAILSAFE);
}
break;
case Failsafe_Action_Hold:
set_mode(mode_hold, MODE_REASON_FAILSAFE);
break;
case Failsafe_Action_SmartRTL:
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
if (!set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
set_mode(mode_hold, MODE_REASON_FAILSAFE);
}
}
break;
case Failsafe_Action_SmartRTL_Hold:
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
set_mode(mode_hold, MODE_REASON_FAILSAFE);
}
break;
}
}
}
}
void Rover::handle_battery_failsafe(const char* type_str, const int8_t action)
{
switch ((Failsafe_Action)action) {
case Failsafe_Action_None:
break;
case Failsafe_Action_SmartRTL:
if (set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
break;
}
FALLTHROUGH;
case Failsafe_Action_RTL:
if (set_mode(mode_rtl, MODE_REASON_FAILSAFE)) {
break;
}
FALLTHROUGH;
case Failsafe_Action_Hold:
set_mode(mode_hold, MODE_REASON_FAILSAFE);
break;
case Failsafe_Action_SmartRTL_Hold:
if (!set_mode(mode_smartrtl, MODE_REASON_FAILSAFE)) {
set_mode(mode_hold, MODE_REASON_FAILSAFE);
}
break;
case Failsafe_Action_Terminate:
#if ADVANCED_FAILSAFE == ENABLED
char battery_type_str[17];
snprintf(battery_type_str, 17, "%s battery", type_str);
g2.afs.gcs_terminate(true, battery_type_str);
#else
arming.disarm();
#endif // ADVANCED_FAILSAFE == ENABLED
break;
}
}
#if ADVANCED_FAILSAFE == ENABLED
/*
check for AFS failsafe check
*/
void Rover::afs_fs_check(void)
{
// perform AFS failsafe checks
g2.afs.check(failsafe.last_heartbeat_ms, g2.fence.get_breaches() != 0, failsafe.last_valid_rc_ms);
}
#endif