CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Blimp/events.cpp
Views: 1798
1
#include "Blimp.h"
2
3
/*
4
* This event will be called when the failsafe changes
5
* boolean failsafe reflects the current state
6
*/
7
8
#include <AP_Vehicle/AP_MultiCopter.h>
9
10
bool Blimp::failsafe_option(FailsafeOption opt) const
11
{
12
return (g2.fs_options & (uint32_t)opt);
13
}
14
15
void Blimp::failsafe_radio_on_event()
16
{
17
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);
18
19
// set desired action based on FS_THR_ENABLE parameter
20
Failsafe_Action desired_action;
21
switch (g.failsafe_throttle) {
22
case FS_THR_DISABLED:
23
desired_action = Failsafe_Action_None;
24
break;
25
case FS_THR_ENABLED_ALWAYS_LAND:
26
desired_action = Failsafe_Action_Land;
27
break;
28
default:
29
desired_action = Failsafe_Action_Land;
30
}
31
32
// Conditions to deviate from FS_THR_ENABLE selection and send specific GCS warning
33
if (should_disarm_on_failsafe()) {
34
// should immediately disarm when we're on the ground
35
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Disarming");
36
arming.disarm(AP_Arming::Method::RADIOFAILSAFE);
37
desired_action = Failsafe_Action_None;
38
39
} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {
40
// Allow landing to continue when battery failsafe requires it (not a user option)
41
gcs().send_text(MAV_SEVERITY_WARNING, "Radio + Battery Failsafe - Continuing Landing");
42
desired_action = Failsafe_Action_Land;
43
44
} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {
45
// Allow landing to continue when FS_OPTIONS is set to continue landing
46
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Landing");
47
desired_action = Failsafe_Action_Land;
48
49
} else {
50
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe");
51
}
52
53
// Call the failsafe action handler
54
do_failsafe_action(desired_action, ModeReason::RADIO_FAILSAFE);
55
}
56
57
// failsafe_off_event - respond to radio contact being regained
58
void Blimp::failsafe_radio_off_event()
59
{
60
// no need to do anything except log the error as resolved
61
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
62
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);
63
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared");
64
}
65
66
void Blimp::handle_battery_failsafe(const char *type_str, const int8_t action)
67
{
68
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);
69
70
Failsafe_Action desired_action = (Failsafe_Action)action;
71
72
// Conditions to deviate from BATT_FS_XXX_ACT parameter setting
73
if (should_disarm_on_failsafe()) {
74
// should immediately disarm when we're on the ground
75
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
76
desired_action = Failsafe_Action_None;
77
gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Disarming");
78
79
} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING) && desired_action != Failsafe_Action_None) {
80
// Allow landing to continue when FS_OPTIONS is set to continue when landing
81
desired_action = Failsafe_Action_Land;
82
gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Continuing Landing");
83
} else {
84
gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe");
85
}
86
87
// Battery FS options already use the Failsafe_Options enum. So use them directly.
88
do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE);
89
90
}
91
// failsafe_gcs_check - check for ground station failsafe
92
void Blimp::failsafe_gcs_check()
93
{
94
// Bypass GCS failsafe checks if disabled or GCS never connected
95
if (g.failsafe_gcs == FS_GCS_DISABLED) {
96
return;
97
}
98
99
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
100
if (gcs_last_seen_ms == 0) {
101
return;
102
}
103
104
// calc time since last gcs update
105
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
106
const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;
107
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
108
109
// Determine which event to trigger
110
if (last_gcs_update_ms < gcs_timeout_ms && failsafe.gcs) {
111
// Recovery from a GCS failsafe
112
set_failsafe_gcs(false);
113
// failsafe_gcs_off_event();
114
115
} else if (last_gcs_update_ms < gcs_timeout_ms && !failsafe.gcs) {
116
// No problem, do nothing
117
118
} else if (last_gcs_update_ms > gcs_timeout_ms && failsafe.gcs) {
119
// Already in failsafe, do nothing
120
121
} else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) {
122
// New GCS failsafe event, trigger events
123
set_failsafe_gcs(true);
124
arming.disarm(AP_Arming::Method::GCSFAILSAFE); // failsafe_gcs_on_event() should replace this when written
125
}
126
}
127
128
bool Blimp::should_disarm_on_failsafe()
129
{
130
if (ap.in_arming_delay) {
131
return true;
132
}
133
134
switch (control_mode) {
135
case Mode::Number::MANUAL:
136
default:
137
// if landed disarm
138
return ap.land_complete;
139
}
140
}
141
142
143
void Blimp::do_failsafe_action(Failsafe_Action action, ModeReason reason)
144
{
145
146
// Execute the specified desired_action
147
switch (action) {
148
case Failsafe_Action_None:
149
return;
150
case Failsafe_Action_Land:
151
set_mode_land_failsafe(reason);
152
break;
153
case Failsafe_Action_Terminate: {
154
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);
155
}
156
break;
157
}
158
}
159
160
// check for gps glitch failsafe
161
void Blimp::gpsglitch_check()
162
{
163
// get filter status
164
nav_filter_status filt_status = inertial_nav.get_filter_status();
165
bool gps_glitching = filt_status.flags.gps_glitching;
166
167
// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS
168
if (ap.gps_glitching != gps_glitching) {
169
ap.gps_glitching = gps_glitching;
170
if (gps_glitching) {
171
LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);
172
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch");
173
} else {
174
LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);
175
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");
176
}
177
}
178
}
179
180