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