Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/AP_Arming_Plane.cpp
4183 views
1
/*
2
additional arming checks for plane
3
*/
4
#include "AP_Arming_Plane.h"
5
#include "Plane.h"
6
7
#include "qautotune.h"
8
9
constexpr uint32_t AP_ARMING_DELAY_MS = 2000; // delay from arming to start of motor spoolup
10
11
const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {
12
// variables from parent vehicle
13
AP_NESTEDGROUPINFO(AP_Arming, 0),
14
15
// index 3 was RUDDER and should not be used
16
17
#if AP_PLANE_BLACKBOX_LOGGING
18
// @Param: BBOX_SPD
19
// @DisplayName: Blackbox speed
20
// @Description: This is a 3D GPS speed threshold above which we will force arm the vehicle to start logging. WARNING: This should only be used on a vehicle with no propellers attached to the flight controller and when the flight controller is not in control of the vehicle.
21
// @Units: m/s
22
// @Increment: 1
23
// @Range: 1 20
24
// @User: Advanced
25
AP_GROUPINFO("BBOX_SPD", 4, AP_Arming_Plane, blackbox_speed, 5),
26
#endif // AP_PLANE_BLACKBOX_LOGGING
27
28
AP_GROUPEND
29
};
30
31
// expected to return true if the terrain database is required to have
32
// all data loaded
33
bool AP_Arming_Plane::terrain_database_required() const
34
{
35
#if AP_TERRAIN_AVAILABLE
36
if (plane.g.terrain_follow) {
37
return true;
38
}
39
#endif
40
return AP_Arming::terrain_database_required();
41
}
42
43
/*
44
additional arming checks for plane
45
46
*/
47
bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
48
{
49
if (armed || require == (uint8_t)Required::NO) {
50
// if we are already armed or don't need any arming checks
51
// then skip the checks
52
return true;
53
}
54
if (!hal.scheduler->is_system_initialized()) {
55
check_failed(display_failure, "System not initialised");
56
return false;
57
}
58
//are arming checks disabled?
59
if (checks_to_perform == 0) {
60
return mandatory_checks(display_failure);
61
}
62
if (hal.util->was_watchdog_armed()) {
63
// on watchdog reset bypass arming checks to allow for
64
// in-flight arming if we were armed before the reset. This
65
// allows a reset on a BVLOS flight to return home if the
66
// operator can command arming over telemetry
67
return true;
68
}
69
70
// call parent class checks
71
bool ret = AP_Arming::pre_arm_checks(display_failure);
72
73
#if AP_AIRSPEED_ENABLED
74
// Check airspeed sensor
75
ret &= AP_Arming::airspeed_checks(display_failure);
76
#endif
77
78
if (plane.aparm.roll_limit < 3) {
79
check_failed(display_failure, "ROLL_LIMIT_DEG too small (%.1f)", plane.aparm.roll_limit.get());
80
ret = false;
81
}
82
83
if (plane.aparm.pitch_limit_max < 3) {
84
check_failed(display_failure, "PTCH_LIM_MAX_DEG too small (%.1f)", plane.aparm.pitch_limit_max.get());
85
ret = false;
86
}
87
88
if (plane.aparm.pitch_limit_min > -3) {
89
check_failed(display_failure, "PTCH_LIM_MIN_DEG too large (%.1f)", plane.aparm.pitch_limit_min.get());
90
ret = false;
91
}
92
93
if (plane.aparm.airspeed_min < MIN_AIRSPEED_MIN) {
94
check_failed(display_failure, "AIRSPEED_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);
95
ret = false;
96
}
97
98
if (plane.channel_throttle->get_reverse() &&
99
plane.g.throttle_fs_enabled != Plane::ThrFailsafe::Disabled &&
100
plane.g.throttle_fs_value <
101
plane.channel_throttle->get_radio_max()) {
102
check_failed(display_failure, "Invalid THR_FS_VALUE for rev throttle");
103
ret = false;
104
}
105
106
ret &= rc_received_if_enabled_check(display_failure);
107
108
#if HAL_QUADPLANE_ENABLED
109
ret &= quadplane_checks(display_failure);
110
#endif
111
112
// check adsb avoidance failsafe
113
if (plane.failsafe.adsb) {
114
check_failed(display_failure, "ADSB threat detected");
115
ret = false;
116
}
117
118
if (plane.flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM)){
119
int16_t trim = plane.channel_throttle->get_radio_trim();
120
if (trim < 1250 || trim > 1750) {
121
check_failed(display_failure, "Throttle trim not near center stick(%u)",trim );
122
ret = false;
123
}
124
}
125
126
if (plane.mission.get_in_landing_sequence_flag() &&
127
!plane.mission.starts_with_takeoff_cmd()) {
128
check_failed(display_failure,"In landing sequence");
129
ret = false;
130
}
131
132
char failure_msg[50] {};
133
if (!plane.control_mode->pre_arm_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
134
check_failed(display_failure, "%s %s", plane.control_mode->name(), failure_msg);
135
return false;
136
}
137
138
return ret;
139
}
140
141
bool AP_Arming_Plane::mandatory_checks(bool display_failure)
142
{
143
bool ret = true;
144
145
ret &= rc_received_if_enabled_check(display_failure);
146
147
// Call parent class checks
148
ret &= AP_Arming::mandatory_checks(display_failure);
149
150
return ret;
151
}
152
153
154
#if HAL_QUADPLANE_ENABLED
155
bool AP_Arming_Plane::quadplane_checks(bool display_failure)
156
{
157
if (!plane.quadplane.enabled()) {
158
return true;
159
}
160
161
if (!plane.quadplane.available()) {
162
check_failed(display_failure, "Quadplane enabled but not running");
163
return false;
164
}
165
166
bool ret = true;
167
168
if (plane.scheduler.get_loop_rate_hz() < 100) {
169
check_failed(display_failure, "quadplane needs SCHED_LOOP_RATE >= 100");
170
ret = false;
171
}
172
173
char failure_msg[50] {};
174
if (!plane.quadplane.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
175
check_failed(display_failure, "Motors: %s", failure_msg);
176
ret = false;
177
}
178
179
// lean angle parameter check
180
if (plane.quadplane.aparm.angle_max < 1000 || plane.quadplane.aparm.angle_max > 8000) {
181
check_failed(Check::PARAMETERS, display_failure, "Check Q_ANGLE_MAX");
182
ret = false;
183
}
184
185
if ((plane.quadplane.tailsitter.enable > 0) && (plane.quadplane.tiltrotor.enable > 0)) {
186
check_failed(Check::PARAMETERS, display_failure, "set TAILSIT_ENABLE 0 or TILT_ENABLE 0");
187
ret = false;
188
189
} else {
190
191
if ((plane.quadplane.tailsitter.enable > 0) && !plane.quadplane.tailsitter.enabled()) {
192
check_failed(Check::PARAMETERS, display_failure, "tailsitter setup not complete, reboot");
193
ret = false;
194
}
195
196
if ((plane.quadplane.tiltrotor.enable > 0) && !plane.quadplane.tiltrotor.enabled()) {
197
check_failed(Check::PARAMETERS, display_failure, "tiltrotor setup not complete, reboot");
198
ret = false;
199
}
200
}
201
202
// ensure controllers are OK with us arming:
203
if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
204
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
205
ret = false;
206
}
207
if (!plane.quadplane.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {
208
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
209
ret = false;
210
}
211
212
/*
213
Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters
214
*/
215
if (check_enabled(Check::PARAMETERS) &&
216
is_zero(plane.quadplane.assist.speed) &&
217
!plane.quadplane.tailsitter.enabled()) {
218
check_failed(display_failure,"Q_ASSIST_SPEED is not set");
219
ret = false;
220
}
221
222
if ((plane.quadplane.tailsitter.enable > 0) && (plane.quadplane.q_fwd_thr_use != QuadPlane::FwdThrUse::OFF)) {
223
check_failed(Check::PARAMETERS, display_failure, "set Q_FWD_THR_USE to 0");
224
ret = false;
225
}
226
227
return ret;
228
}
229
#endif // HAL_QUADPLANE_ENABLED
230
231
bool AP_Arming_Plane::ins_checks(bool display_failure)
232
{
233
// call parent class checks
234
if (!AP_Arming::ins_checks(display_failure)) {
235
return false;
236
}
237
238
// additional plane specific checks
239
if (check_enabled(Check::INS)) {
240
char failure_msg[50] = {};
241
if (!AP::ahrs().pre_arm_check(true, failure_msg, sizeof(failure_msg))) {
242
check_failed(Check::INS, display_failure, "AHRS: %s", failure_msg);
243
return false;
244
}
245
}
246
247
return true;
248
}
249
250
bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
251
{
252
253
//are arming checks disabled?
254
if (checks_to_perform == 0) {
255
return true;
256
}
257
258
if (hal.util->was_watchdog_armed()) {
259
// on watchdog reset bypass arming checks to allow for
260
// in-flight arming if we were armed before the reset. This
261
// allows a reset on a BVLOS flight to return home if the
262
// operator can command arming over telemetry
263
gcs().send_text(MAV_SEVERITY_WARNING, "watchdog: Bypassing arming checks");
264
return true;
265
}
266
267
// call parent class checks
268
return AP_Arming::arm_checks(method);
269
}
270
271
/*
272
update HAL soft arm state
273
*/
274
void AP_Arming_Plane::change_arm_state(void)
275
{
276
update_soft_armed();
277
#if HAL_QUADPLANE_ENABLED
278
plane.quadplane.set_armed(hal.util->get_soft_armed());
279
#endif
280
}
281
282
bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_checks)
283
{
284
if (!AP_Arming::arm(method, do_arming_checks)) {
285
return false;
286
}
287
288
if (plane.update_home()) {
289
// after update_home the home position could still be
290
// different from the current_loc if the EKF refused the
291
// resetHeightDatum call. If we are updating home then we want
292
// to force the home to be the current_loc so relative alt
293
// takeoffs work correctly
294
if (plane.ahrs.set_home(plane.current_loc)) {
295
// update current_loc
296
plane.update_current_loc();
297
}
298
}
299
300
change_arm_state();
301
302
// rising edge of delay_arming oneshot
303
delay_arming = true;
304
305
#if MODE_AUTOLAND_ENABLED
306
plane.mode_autoland.arm_check();
307
#endif
308
309
if (method == AP_Arming::Method::RUDDER) {
310
// initialise the timer used to warn the user they're holding
311
// their stick over:
312
plane.takeoff_state.rudder_takeoff_warn_ms = AP_HAL::millis();
313
}
314
315
send_arm_disarm_statustext("Throttle armed");
316
317
return true;
318
}
319
320
/*
321
disarm motors
322
*/
323
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
324
{
325
if (do_disarm_checks &&
326
(AP_Arming::method_is_GCS(method) ||
327
method == AP_Arming::Method::RUDDER)) {
328
if (plane.is_flying()) {
329
// don't allow mavlink or rudder disarm while flying
330
return false;
331
}
332
}
333
334
if (!AP_Arming::disarm(method, do_disarm_checks)) {
335
return false;
336
}
337
if (plane.control_mode != &plane.mode_auto) {
338
// reset the mission on disarm if we are not in auto
339
plane.mission.reset();
340
}
341
342
// suppress the throttle in auto-throttle modes
343
plane.throttle_suppressed = plane.control_mode->does_auto_throttle();
344
345
// if no airmode switch assigned, ensure airmode is off:
346
#if HAL_QUADPLANE_ENABLED
347
if ((plane.quadplane.air_mode == AirMode::ON) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) {
348
plane.quadplane.air_mode = AirMode::OFF;
349
}
350
#endif
351
352
//only log if disarming was successful
353
change_arm_state();
354
355
#if QAUTOTUNE_ENABLED
356
// Possibly save auto tuned parameters
357
plane.quadplane.qautotune.disarmed(plane.control_mode == &plane.mode_qautotune);
358
#endif
359
360
// re-initialize speed variable used in AUTO and GUIDED for
361
// DO_CHANGE_SPEED commands
362
plane.new_airspeed_cm = -1;
363
364
#if MODE_AUTOLAND_ENABLED
365
// takeoff direction always cleared on disarm
366
plane.takeoff_state.initial_direction.initialized = false;
367
#endif
368
send_arm_disarm_statustext("Throttle disarmed");
369
return true;
370
}
371
372
void AP_Arming_Plane::update_soft_armed()
373
{
374
bool _armed = is_armed();
375
#if HAL_QUADPLANE_ENABLED
376
if (plane.quadplane.motor_test.running){
377
_armed = true;
378
}
379
#endif
380
381
hal.util->set_soft_armed(_armed);
382
#if HAL_LOGGING_ENABLED
383
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());
384
#endif
385
386
// update delay_arming oneshot
387
if (delay_arming &&
388
(AP_HAL::millis() - hal.util->get_last_armed_change() >= AP_ARMING_DELAY_MS)) {
389
390
delay_arming = false;
391
}
392
393
#if AP_PLANE_BLACKBOX_LOGGING
394
if (blackbox_speed > 0) {
395
const float speed3d = plane.gps.status() >= AP_GPS::GPS_OK_FIX_3D?plane.gps.velocity().length():0;
396
const uint32_t now = AP_HAL::millis();
397
if (speed3d > blackbox_speed) {
398
last_over_3dspeed_ms = now;
399
}
400
if (!_armed && speed3d > blackbox_speed) {
401
// force safety on so we don't run motors
402
hal.rcout->force_safety_on();
403
AP_Param::set_by_name("RC_PROTOCOLS", 0);
404
arm(Method::BLACKBOX, false);
405
gcs().send_text(MAV_SEVERITY_WARNING, "BlackBox: arming at %.1f m/s", speed3d);
406
}
407
if (_armed && now - last_over_3dspeed_ms > 20000U) {
408
gcs().send_text(MAV_SEVERITY_WARNING, "BlackBox: disarming at %.1f m/s", speed3d);
409
disarm(Method::BLACKBOX, false);
410
}
411
}
412
#endif
413
}
414
415
/*
416
extra plane mission checks
417
*/
418
bool AP_Arming_Plane::mission_checks(bool report)
419
{
420
// base checks
421
bool ret = AP_Arming::mission_checks(report);
422
if (plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
423
if (plane.mission.contains_item(MAV_CMD_DO_LAND_START)) {
424
ret = false;
425
check_failed(Check::MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");
426
}
427
if (plane.mission.contains_item(MAV_CMD_DO_RETURN_PATH_START)) {
428
ret = false;
429
check_failed(Check::MISSION, report, "DO_RETURN_PATH_START set and RTL_AUTOLAND disabled");
430
}
431
}
432
#if HAL_QUADPLANE_ENABLED
433
if (plane.quadplane.available()) {
434
const uint16_t num_commands = plane.mission.num_commands();
435
AP_Mission::Mission_Command prev_cmd {};
436
for (uint16_t i=1; i<num_commands; i++) {
437
AP_Mission::Mission_Command cmd;
438
if (!plane.mission.read_cmd_from_storage(i, cmd)) {
439
break;
440
}
441
if (plane.is_land_command(cmd.id) &&
442
prev_cmd.id == MAV_CMD_NAV_WAYPOINT) {
443
const float dist = cmd.content.location.get_distance(prev_cmd.content.location);
444
const float tecs_land_speed = plane.TECS_controller.get_land_airspeed();
445
const float landing_speed = is_positive(tecs_land_speed)?tecs_land_speed:plane.aparm.airspeed_cruise;
446
const float min_dist = 0.75 * plane.quadplane.stopping_distance_m(sq(landing_speed));
447
if (dist < min_dist) {
448
ret = false;
449
check_failed(Check::MISSION, report, "VTOL land too short, min %.0fm", min_dist);
450
}
451
}
452
prev_cmd = cmd;
453
}
454
}
455
#endif
456
return ret;
457
}
458
459
// Checks rc has been received if it is configured to be used
460
bool AP_Arming_Plane::rc_received_if_enabled_check(bool display_failure)
461
{
462
if (rc().enabled_protocols() == 0) {
463
// No protocols enabled, will never get RC, don't block arming
464
return true;
465
}
466
467
// If RC failsafe is enabled we must receive RC before arming
468
if ((plane.g.throttle_fs_enabled == Plane::ThrFailsafe::Enabled) &&
469
!(rc().has_had_rc_receiver() || rc().has_had_rc_override())) {
470
check_failed(display_failure, "Waiting for RC");
471
return false;
472
}
473
474
return true;
475
}
476
477