Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/failsafe.cpp
9317 views
1
/*
2
failsafe support
3
Andrew Tridgell, December 2011
4
*/
5
6
#include "Rover.h"
7
8
#include <stdio.h>
9
10
/*
11
our failsafe strategy is to detect main loop lockup and disarm.
12
*/
13
14
/*
15
this failsafe_check function is called from the core timer interrupt
16
at 1kHz.
17
*/
18
void Rover::failsafe_check()
19
{
20
static uint16_t last_ticks;
21
static uint32_t last_timestamp;
22
const uint32_t tnow = AP_HAL::micros();
23
24
const uint16_t ticks = scheduler.ticks();
25
if (ticks != last_ticks) {
26
// the main loop is running, all is OK
27
last_ticks = ticks;
28
last_timestamp = tnow;
29
return;
30
}
31
32
if (tnow - last_timestamp > 200000) {
33
// we have gone at least 0.2 seconds since the main loop
34
// ran. That means we're in trouble, or perhaps are in
35
// an initialisation routine or log erase. disarm the motors
36
// To-Do: log error
37
if (arming.is_armed()) {
38
// disarm motors
39
arming.disarm(AP_Arming::Method::CPUFAILSAFE);
40
}
41
}
42
}
43
44
/*
45
called to set/unset a failsafe event.
46
*/
47
void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on)
48
{
49
uint8_t old_bits = failsafe.bits;
50
if (on) {
51
failsafe.bits |= failsafe_type;
52
} else {
53
failsafe.bits &= ~failsafe_type;
54
}
55
if (old_bits == 0 && failsafe.bits != 0) {
56
// a failsafe event has started
57
failsafe.start_time = millis();
58
}
59
if (failsafe.triggered != 0 && failsafe.bits == 0) {
60
// a failsafe event has ended
61
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Failsafe Cleared", type_str);
62
}
63
64
failsafe.triggered &= failsafe.bits;
65
66
if (failsafe_type == FAILSAFE_EVENT_GCS) {
67
AP_Notify::flags.failsafe_gcs = on;
68
}
69
70
if ((failsafe.triggered == 0) &&
71
(failsafe.bits != 0) &&
72
(millis() - failsafe.start_time > g.fs_timeout * 1000) &&
73
(control_mode != &mode_rtl) &&
74
((control_mode != &mode_hold || (g2.fs_options & (uint32_t)Failsafe_Options::Failsafe_Option_Active_In_Hold)))) {
75
failsafe.triggered = failsafe.bits;
76
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s Failsafe", type_str);
77
78
// clear rc overrides
79
RC_Channels::clear_overrides();
80
81
if ((control_mode == &mode_auto) &&
82
((failsafe_type == FAILSAFE_EVENT_THROTTLE && g.fs_throttle_enabled == FS_THR_ENABLED_CONTINUE_MISSION) ||
83
(failsafe_type == FAILSAFE_EVENT_GCS && g.fs_gcs_enabled == FS_GCS_ENABLED_CONTINUE_MISSION))) {
84
// continue with mission in auto mode
85
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failsafe - Continuing Auto Mode");
86
} else {
87
switch ((FailsafeAction)g.fs_action.get()) {
88
case FailsafeAction::None:
89
break;
90
case FailsafeAction::SmartRTL:
91
if (set_mode(mode_smartrtl, ModeReason::FAILSAFE)) {
92
break;
93
}
94
FALLTHROUGH;
95
case FailsafeAction::RTL:
96
if (set_mode(mode_rtl, ModeReason::FAILSAFE)) {
97
break;
98
}
99
FALLTHROUGH;
100
case FailsafeAction::Hold:
101
set_mode(mode_hold, ModeReason::FAILSAFE);
102
break;
103
case FailsafeAction::SmartRTL_Hold:
104
if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) {
105
set_mode(mode_hold, ModeReason::FAILSAFE);
106
}
107
break;
108
case FailsafeAction::Loiter_Hold:
109
if (!set_mode(mode_loiter, ModeReason::FAILSAFE)) {
110
set_mode(mode_hold, ModeReason::FAILSAFE);
111
}
112
break;
113
case FailsafeAction::Terminate:
114
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);
115
break;
116
}
117
}
118
}
119
}
120
121
void Rover::handle_battery_failsafe(const char* type_str, const int8_t action)
122
{
123
switch ((FailsafeAction)action) {
124
case FailsafeAction::None:
125
break;
126
case FailsafeAction::SmartRTL:
127
if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) {
128
break;
129
}
130
FALLTHROUGH;
131
case FailsafeAction::RTL:
132
if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) {
133
break;
134
}
135
FALLTHROUGH;
136
case FailsafeAction::Hold:
137
set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE);
138
break;
139
case FailsafeAction::Loiter_Hold:
140
if (!set_mode(mode_loiter, ModeReason::BATTERY_FAILSAFE)) {
141
set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE);
142
}
143
break;
144
case FailsafeAction::SmartRTL_Hold:
145
if (!set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) {
146
set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE);
147
}
148
break;
149
case FailsafeAction::Terminate:
150
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
151
char battery_type_str[17];
152
snprintf(battery_type_str, 17, "%s battery", type_str);
153
g2.afs.gcs_terminate(true, battery_type_str);
154
#else
155
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
156
#endif // AP_ROVER_ADVANCED_FAILSAFE_ENABLED
157
break;
158
}
159
}
160
161
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
162
/*
163
check for AFS failsafe check
164
*/
165
void Rover::afs_fs_check(void)
166
{
167
// perform AFS failsafe checks
168
g2.afs.check(failsafe.last_valid_rc_ms);
169
}
170
#endif
171
172