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/AP_Arming.cpp
Views: 1798
1
#include "Blimp.h"
2
3
bool AP_Arming_Blimp::pre_arm_checks(bool display_failure)
4
{
5
const bool passed = run_pre_arm_checks(display_failure);
6
set_pre_arm_check(passed);
7
return passed;
8
}
9
10
// perform pre-arm checks
11
// return true if the checks pass successfully
12
bool AP_Arming_Blimp::run_pre_arm_checks(bool display_failure)
13
{
14
// exit immediately if already armed
15
if (blimp.motors->armed()) {
16
return true;
17
}
18
19
// check if motor interlock and Emergency Stop aux switches are used
20
// at the same time. This cannot be allowed.
21
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&
22
rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)) {
23
check_failed(display_failure, "Interlock/E-Stop Conflict");
24
return false;
25
}
26
27
// if pre arm checks are disabled run only the mandatory checks
28
if (checks_to_perform == 0) {
29
return mandatory_checks(display_failure);
30
}
31
32
return parameter_checks(display_failure)
33
#if AP_FENCE_ENABLED
34
& fence_checks(display_failure)
35
#endif
36
& motor_checks(display_failure)
37
& gcs_failsafe_check(display_failure)
38
& alt_checks(display_failure)
39
& AP_Arming::pre_arm_checks(display_failure);
40
}
41
42
bool AP_Arming_Blimp::barometer_checks(bool display_failure)
43
{
44
if (!AP_Arming::barometer_checks(display_failure)) {
45
return false;
46
}
47
48
bool ret = true;
49
// check Baro
50
if (check_enabled(ARMING_CHECK_BARO)) {
51
// Check baro & inav alt are within 1m if EKF is operating in an absolute position mode.
52
// Do not check if intending to operate in a ground relative height mode as EKF will output a ground relative height
53
// that may differ from the baro height due to baro drift.
54
nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();
55
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
56
if (using_baro_ref) {
57
if (fabsf(blimp.inertial_nav.get_position_z_up_cm() - blimp.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
58
check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");
59
ret = false;
60
}
61
}
62
}
63
return ret;
64
}
65
66
bool AP_Arming_Blimp::ins_checks(bool display_failure)
67
{
68
bool ret = AP_Arming::ins_checks(display_failure);
69
70
if (check_enabled(ARMING_CHECK_INS)) {
71
72
// get ekf attitude (if bad, it's usually the gyro biases)
73
if (!pre_arm_ekf_attitude_check()) {
74
check_failed(ARMING_CHECK_INS, display_failure, "EKF attitude is bad");
75
ret = false;
76
}
77
}
78
79
return ret;
80
}
81
82
bool AP_Arming_Blimp::board_voltage_checks(bool display_failure)
83
{
84
if (!AP_Arming::board_voltage_checks(display_failure)) {
85
return false;
86
}
87
88
// check battery voltage
89
if (check_enabled(ARMING_CHECK_VOLTAGE)) {
90
if (blimp.battery.has_failsafed()) {
91
check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");
92
return false;
93
}
94
95
// call parent battery checks
96
if (!AP_Arming::battery_checks(display_failure)) {
97
return false;
98
}
99
}
100
101
return true;
102
}
103
104
bool AP_Arming_Blimp::parameter_checks(bool display_failure)
105
{
106
// check various parameter values
107
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
108
109
// failsafe parameter checks
110
if (blimp.g.failsafe_throttle) {
111
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
112
if (blimp.channel_up->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) {
113
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");
114
return false;
115
}
116
}
117
}
118
119
return true;
120
}
121
122
// check motor setup was successful
123
bool AP_Arming_Blimp::motor_checks(bool display_failure)
124
{
125
// check motors initialised correctly
126
if (!blimp.motors->initialised_ok()) {
127
check_failed(display_failure, "Check firmware or FRAME_CLASS");
128
return false;
129
}
130
131
// further checks enabled with parameters
132
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
133
return true;
134
}
135
136
return true;
137
}
138
139
bool AP_Arming_Blimp::rc_calibration_checks(bool display_failure)
140
{
141
return true;
142
}
143
144
// performs pre_arm gps related checks and returns true if passed
145
bool AP_Arming_Blimp::gps_checks(bool display_failure)
146
{
147
// run mandatory gps checks first
148
if (!mandatory_gps_checks(display_failure)) {
149
AP_Notify::flags.pre_arm_gps_check = false;
150
return false;
151
}
152
153
// check if flight mode requires GPS
154
bool mode_requires_gps = blimp.flightmode->requires_GPS();
155
156
157
// return true if GPS is not required
158
if (!mode_requires_gps) {
159
AP_Notify::flags.pre_arm_gps_check = true;
160
return true;
161
}
162
163
// return true immediately if gps check is disabled
164
if (!check_enabled(ARMING_CHECK_GPS)) {
165
AP_Notify::flags.pre_arm_gps_check = true;
166
return true;
167
}
168
169
// warn about hdop separately - to prevent user confusion with no gps lock
170
if (blimp.gps.get_hdop() > blimp.g.gps_hdop_good) {
171
check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP");
172
AP_Notify::flags.pre_arm_gps_check = false;
173
return false;
174
}
175
176
// call parent gps checks
177
if (!AP_Arming::gps_checks(display_failure)) {
178
AP_Notify::flags.pre_arm_gps_check = false;
179
return false;
180
}
181
182
// if we got here all must be ok
183
AP_Notify::flags.pre_arm_gps_check = true;
184
return true;
185
}
186
187
// check ekf attitude is acceptable
188
bool AP_Arming_Blimp::pre_arm_ekf_attitude_check()
189
{
190
// get ekf filter status
191
nav_filter_status filt_status = blimp.inertial_nav.get_filter_status();
192
193
return filt_status.flags.attitude;
194
}
195
196
// performs mandatory gps checks. returns true if passed
197
bool AP_Arming_Blimp::mandatory_gps_checks(bool display_failure)
198
{
199
// always check if inertial nav has started and is ready
200
const auto &ahrs = AP::ahrs();
201
char failure_msg[50] = {};
202
if (!ahrs.pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
203
check_failed(display_failure, "AHRS: %s", failure_msg);
204
return false;
205
}
206
207
// check if flight mode requires GPS
208
bool mode_requires_gps = blimp.flightmode->requires_GPS();
209
210
if (mode_requires_gps) {
211
if (!blimp.position_ok()) {
212
// vehicle level position estimate checks
213
check_failed(display_failure, "Need Position Estimate");
214
return false;
215
}
216
} else {
217
// return true if GPS is not required
218
return true;
219
}
220
221
// check for GPS glitch (as reported by EKF)
222
nav_filter_status filt_status;
223
if (ahrs.get_filter_status(filt_status)) {
224
if (filt_status.flags.gps_glitching) {
225
check_failed(display_failure, "GPS glitching");
226
return false;
227
}
228
}
229
230
// if we got here all must be ok
231
return true;
232
}
233
234
// Check GCS failsafe
235
bool AP_Arming_Blimp::gcs_failsafe_check(bool display_failure)
236
{
237
if (blimp.failsafe.gcs) {
238
check_failed(display_failure, "GCS failsafe on");
239
return false;
240
}
241
return true;
242
}
243
244
// performs altitude checks. returns true if passed
245
bool AP_Arming_Blimp::alt_checks(bool display_failure)
246
{
247
// always EKF altitude estimate
248
if (!blimp.flightmode->has_manual_throttle() && !blimp.ekf_alt_ok()) {
249
check_failed(display_failure, "Need Alt Estimate");
250
return false;
251
}
252
253
return true;
254
}
255
256
// arm_checks - perform final checks before arming
257
// always called just before arming. Return true if ok to arm
258
// has side-effect that logging is started
259
bool AP_Arming_Blimp::arm_checks(AP_Arming::Method method)
260
{
261
return AP_Arming::arm_checks(method);
262
}
263
264
// mandatory checks that will be run if ARMING_CHECK is zero or arming forced
265
bool AP_Arming_Blimp::mandatory_checks(bool display_failure)
266
{
267
// call mandatory gps checks and update notify status because regular gps checks will not run
268
bool result = mandatory_gps_checks(display_failure);
269
AP_Notify::flags.pre_arm_gps_check = result;
270
271
// call mandatory alt check
272
if (!alt_checks(display_failure)) {
273
result = false;
274
}
275
276
return result & AP_Arming::mandatory_checks(display_failure);
277
}
278
279
void AP_Arming_Blimp::set_pre_arm_check(bool b)
280
{
281
blimp.ap.pre_arm_check = b;
282
AP_Notify::flags.pre_arm_check = b;
283
}
284
285
bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_checks)
286
{
287
static bool in_arm_motors = false;
288
289
// exit immediately if already in this function
290
if (in_arm_motors) {
291
return false;
292
}
293
in_arm_motors = true;
294
295
// return true if already armed
296
if (blimp.motors->armed()) {
297
in_arm_motors = false;
298
return true;
299
}
300
301
if (!AP_Arming::arm(method, do_arming_checks)) {
302
AP_Notify::events.arming_failed = true;
303
in_arm_motors = false;
304
return false;
305
}
306
307
#if HAL_LOGGING_ENABLED
308
// let logger know that we're armed (it may open logs e.g.)
309
AP::logger().set_vehicle_armed(true);
310
#endif
311
312
// notify that arming will occur (we do this early to give plenty of warning)
313
AP_Notify::flags.armed = true;
314
// call notify update a few times to ensure the message gets out
315
for (uint8_t i=0; i<=10; i++) {
316
AP::notify().update();
317
}
318
319
send_arm_disarm_statustext("Arming motors"); //MIR kept in - usually only in SITL
320
321
auto &ahrs = AP::ahrs();
322
323
blimp.initial_armed_bearing = ahrs.yaw_sensor;
324
325
if (!ahrs.home_is_set()) {
326
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
327
ahrs.resetHeightDatum();
328
LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);
329
330
// we have reset height, so arming height is zero
331
blimp.arming_altitude_m = 0;
332
} else if (!ahrs.home_is_locked()) {
333
// Reset home position if it has already been set before (but not locked)
334
if (!blimp.set_home_to_current_location(false)) {
335
// ignore failure
336
}
337
338
// remember the height when we armed
339
blimp.arming_altitude_m = blimp.inertial_nav.get_position_z_up_cm() * 0.01;
340
}
341
342
hal.util->set_soft_armed(true);
343
344
// finally actually arm the motors
345
blimp.motors->armed(true);
346
347
#if HAL_LOGGING_ENABLED
348
// log flight mode in case it was changed while vehicle was disarmed
349
AP::logger().Write_Mode((uint8_t)blimp.control_mode, blimp.control_mode_reason);
350
#endif
351
352
// perf monitor ignores delay due to arming
353
AP::scheduler().perf_info.ignore_this_loop();
354
355
// flag exiting this function
356
in_arm_motors = false;
357
358
// Log time stamp of arming event
359
blimp.arm_time_ms = millis();
360
361
// Start the arming delay
362
blimp.ap.in_arming_delay = true;
363
364
// return success
365
return true;
366
}
367
368
// arming.disarm - disarm motors
369
bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_checks)
370
{
371
// return immediately if we are already disarmed
372
if (!blimp.motors->armed()) {
373
return true;
374
}
375
376
if (!AP_Arming::disarm(method, do_disarm_checks)) {
377
return false;
378
}
379
380
send_arm_disarm_statustext("Disarming motors"); //MIR keeping in - usually only in SITL
381
382
auto &ahrs = AP::ahrs();
383
384
// save compass offsets learned by the EKF if enabled
385
Compass &compass = AP::compass();
386
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LEARN_EKF) {
387
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
388
Vector3f magOffsets;
389
if (ahrs.getMagOffsets(i, magOffsets)) {
390
compass.set_and_save_offsets(i, magOffsets);
391
}
392
}
393
}
394
395
// send disarm command to motors
396
blimp.motors->armed(false);
397
398
#if HAL_LOGGING_ENABLED
399
AP::logger().set_vehicle_armed(false);
400
#endif
401
402
hal.util->set_soft_armed(false);
403
404
blimp.ap.in_arming_delay = false;
405
406
return true;
407
}
408
409