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