Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/RC_Channel_Plane.cpp
9531 views
1
#include "Plane.h"
2
3
#include "RC_Channel_Plane.h"
4
#include "qautotune.h"
5
6
// defining these two macros and including the RC_Channels_VarInfo
7
// header defines the parameter information common to all vehicle
8
// types
9
#define RC_CHANNELS_SUBCLASS RC_Channels_Plane
10
#define RC_CHANNEL_SUBCLASS RC_Channel_Plane
11
12
#include <RC_Channel/RC_Channels_VarInfo.h>
13
14
// note that this callback is not presently used on Plane:
15
int8_t RC_Channels_Plane::flight_mode_channel_number() const
16
{
17
return plane.g.flight_mode_channel.get();
18
}
19
20
bool RC_Channels_Plane::in_rc_failsafe() const
21
{
22
return (plane.rc_failsafe_active() || plane.failsafe.rc_failsafe);
23
}
24
25
bool RC_Channels_Plane::has_valid_input() const
26
{
27
if (in_rc_failsafe()) {
28
return false;
29
}
30
if (plane.failsafe.throttle_counter != 0) {
31
return false;
32
}
33
return RC_Channels::has_valid_input();
34
}
35
36
RC_Channel * RC_Channels_Plane::get_arming_channel(void) const
37
{
38
return plane.channel_rudder;
39
}
40
41
void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number,
42
const AuxSwitchPos ch_flag)
43
{
44
switch(ch_flag) {
45
case AuxSwitchPos::HIGH: {
46
// engage mode (if not possible we remain in current flight mode)
47
plane.set_mode_by_number(number, ModeReason::AUX_FUNCTION);
48
break;
49
}
50
default:
51
// return to flight mode switch's flight mode if we are currently
52
// in this mode
53
if (plane.control_mode->mode_number() == number) {
54
rc().reset_mode_switch();
55
}
56
}
57
}
58
59
#if HAL_QUADPLANE_ENABLED
60
void RC_Channel_Plane::do_aux_function_q_assist_state(AuxSwitchPos ch_flag)
61
{
62
switch(ch_flag) {
63
case AuxSwitchPos::HIGH:
64
gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Force enabled");
65
plane.quadplane.assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED);
66
break;
67
68
case AuxSwitchPos::MIDDLE:
69
gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Enabled");
70
plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_ENABLED);
71
break;
72
73
case AuxSwitchPos::LOW:
74
gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Disabled");
75
plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_DISABLED);
76
break;
77
}
78
}
79
#endif // HAL_QUADPLANE_ENABLED
80
81
void RC_Channel_Plane::do_aux_function_crow_mode(AuxSwitchPos ch_flag)
82
{
83
switch(ch_flag) {
84
case AuxSwitchPos::HIGH:
85
plane.crow_mode = Plane::CrowMode::CROW_DISABLED;
86
gcs().send_text(MAV_SEVERITY_INFO, "Crow Flaps Disabled");
87
break;
88
case AuxSwitchPos::MIDDLE:
89
gcs().send_text(MAV_SEVERITY_INFO, "Progressive Crow Flaps");
90
plane.crow_mode = Plane::CrowMode::PROGRESSIVE;
91
break;
92
case AuxSwitchPos::LOW:
93
plane.crow_mode = Plane::CrowMode::NORMAL;
94
gcs().send_text(MAV_SEVERITY_INFO, "Normal Crow Flaps");
95
break;
96
}
97
}
98
99
#if HAL_SOARING_ENABLED
100
void RC_Channel_Plane::do_aux_function_soaring_3pos(AuxSwitchPos ch_flag)
101
{
102
SoaringController::ActiveStatus desired_state = SoaringController::ActiveStatus::SOARING_DISABLED;
103
104
switch (ch_flag) {
105
case AuxSwitchPos::LOW:
106
desired_state = SoaringController::ActiveStatus::SOARING_DISABLED;
107
break;
108
case AuxSwitchPos::MIDDLE:
109
desired_state = SoaringController::ActiveStatus::MANUAL_MODE_CHANGE;
110
break;
111
case AuxSwitchPos::HIGH:
112
desired_state = SoaringController::ActiveStatus::AUTO_MODE_CHANGE;
113
break;
114
}
115
116
plane.g2.soaring_controller.set_pilot_desired_state(desired_state);
117
}
118
#endif
119
120
void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
121
{
122
switch(ch_flag) {
123
case AuxSwitchPos::HIGH:
124
plane.flare_mode = Plane::FlareMode::ENABLED_PITCH_TARGET;
125
break;
126
case AuxSwitchPos::MIDDLE:
127
plane.flare_mode = Plane::FlareMode::ENABLED_NO_PITCH_TARGET;
128
break;
129
case AuxSwitchPos::LOW:
130
plane.flare_mode = Plane::FlareMode::FLARE_DISABLED;
131
break;
132
}
133
}
134
135
136
void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
137
const RC_Channel::AuxSwitchPos ch_flag)
138
{
139
switch(ch_option) {
140
// the following functions do not need to be initialised:
141
case AUX_FUNC::AUTO:
142
case AUX_FUNC::CIRCLE:
143
case AUX_FUNC::ACRO:
144
case AUX_FUNC::TRAINING:
145
case AUX_FUNC::FLAP:
146
case AUX_FUNC::GUIDED:
147
case AUX_FUNC::INVERTED:
148
case AUX_FUNC::LOITER:
149
case AUX_FUNC::MANUAL:
150
case AUX_FUNC::RTL:
151
case AUX_FUNC::TAKEOFF:
152
case AUX_FUNC::FBWA:
153
case AUX_FUNC::AIRBRAKE:
154
#if HAL_QUADPLANE_ENABLED
155
case AUX_FUNC::QRTL:
156
case AUX_FUNC::QSTABILIZE:
157
#endif
158
case AUX_FUNC::FBWA_TAILDRAGGER:
159
case AUX_FUNC::FWD_THR:
160
case AUX_FUNC::LANDING_FLARE:
161
#if HAL_PARACHUTE_ENABLED
162
case AUX_FUNC::PARACHUTE_RELEASE:
163
#endif
164
case AUX_FUNC::MODE_SWITCH_RESET:
165
case AUX_FUNC::CRUISE:
166
#if HAL_QUADPLANE_ENABLED
167
case AUX_FUNC::ARMDISARM_AIRMODE:
168
#endif
169
case AUX_FUNC::PLANE_AUTO_LANDING_ABORT:
170
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
171
case AUX_FUNC::EMERGENCY_LANDING_EN:
172
case AUX_FUNC::FW_AUTOTUNE:
173
case AUX_FUNC::VFWD_THR_OVERRIDE:
174
case AUX_FUNC::PRECISION_LOITER:
175
#if QAUTOTUNE_ENABLED
176
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
177
#endif
178
#if AP_QUICKTUNE_ENABLED
179
case AUX_FUNC::QUICKTUNE:
180
#endif
181
#if MODE_AUTOLAND_ENABLED
182
case AUX_FUNC::AUTOLAND:
183
#endif
184
#if AP_PLANE_SYSTEMID_ENABLED
185
case AUX_FUNC::SYSTEMID:
186
#endif
187
break;
188
case AUX_FUNC::SOARING:
189
#if HAL_QUADPLANE_ENABLED
190
case AUX_FUNC::Q_ASSIST:
191
case AUX_FUNC::AIRMODE:
192
case AUX_FUNC::WEATHER_VANE_ENABLE:
193
#endif
194
#if AP_AIRSPEED_AUTOCAL_ENABLE
195
case AUX_FUNC::ARSPD_CALIBRATE:
196
#endif
197
case AUX_FUNC::TER_DISABLE:
198
case AUX_FUNC::CROW_SELECT:
199
#if AP_ICENGINE_ENABLED
200
case AUX_FUNC::ICE_START_STOP:
201
#endif
202
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT, ch_in);
203
break;
204
205
case AUX_FUNC::REVERSE_THROTTLE:
206
plane.have_reverse_throttle_rc_option = true;
207
// setup input throttle as a range. This is needed as init_aux_function is called
208
// after set_control_channels()
209
if (plane.channel_throttle) {
210
plane.channel_throttle->set_range(100);
211
}
212
// note that we don't call do_aux_function() here as we don't
213
// want to startup with reverse thrust
214
break;
215
216
default:
217
// handle in parent class
218
RC_Channel::init_aux_function(ch_option, ch_flag);
219
break;
220
}
221
}
222
223
// do_aux_function - implement the function invoked by auxiliary switches
224
bool RC_Channel_Plane::do_aux_function(const AuxFuncTrigger &trigger)
225
{
226
const AUX_FUNC &ch_option = trigger.func;
227
const AuxSwitchPos &ch_flag = trigger.pos;
228
229
switch(ch_option) {
230
case AUX_FUNC::INVERTED:
231
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
232
break;
233
234
case AUX_FUNC::REVERSE_THROTTLE:
235
plane.reversed_throttle = (ch_flag == AuxSwitchPos::HIGH);
236
gcs().send_text(MAV_SEVERITY_INFO, "RevThrottle: %s", plane.reversed_throttle?"ENABLE":"DISABLE");
237
break;
238
239
case AUX_FUNC::AUTO:
240
do_aux_function_change_mode(Mode::Number::AUTO, ch_flag);
241
break;
242
243
case AUX_FUNC::CIRCLE:
244
do_aux_function_change_mode(Mode::Number::CIRCLE, ch_flag);
245
break;
246
247
case AUX_FUNC::ACRO:
248
do_aux_function_change_mode(Mode::Number::ACRO, ch_flag);
249
break;
250
251
case AUX_FUNC::TRAINING:
252
do_aux_function_change_mode(Mode::Number::TRAINING, ch_flag);
253
break;
254
255
case AUX_FUNC::LOITER:
256
do_aux_function_change_mode(Mode::Number::LOITER, ch_flag);
257
break;
258
259
case AUX_FUNC::GUIDED:
260
do_aux_function_change_mode(Mode::Number::GUIDED, ch_flag);
261
break;
262
263
case AUX_FUNC::MANUAL:
264
do_aux_function_change_mode(Mode::Number::MANUAL, ch_flag);
265
break;
266
267
case AUX_FUNC::RTL:
268
do_aux_function_change_mode(Mode::Number::RTL, ch_flag);
269
break;
270
271
case AUX_FUNC::TAKEOFF:
272
do_aux_function_change_mode(Mode::Number::TAKEOFF, ch_flag);
273
break;
274
275
case AUX_FUNC::FBWA:
276
do_aux_function_change_mode(Mode::Number::FLY_BY_WIRE_A, ch_flag);
277
break;
278
279
#if HAL_QUADPLANE_ENABLED
280
case AUX_FUNC::QRTL:
281
do_aux_function_change_mode(Mode::Number::QRTL, ch_flag);
282
break;
283
284
case AUX_FUNC::QSTABILIZE:
285
do_aux_function_change_mode(Mode::Number::QSTABILIZE, ch_flag);
286
break;
287
288
case AUX_FUNC::VFWD_THR_OVERRIDE: {
289
const bool enable = (ch_flag == AuxSwitchPos::HIGH);
290
if (enable != plane.quadplane.vfwd_enable_active) {
291
plane.quadplane.vfwd_enable_active = enable;
292
gcs().send_text(MAV_SEVERITY_INFO, "QFwdThr: %s", enable?"ON":"OFF");
293
}
294
break;
295
}
296
#endif
297
298
#if HAL_SOARING_ENABLED
299
case AUX_FUNC::SOARING:
300
do_aux_function_soaring_3pos(ch_flag);
301
break;
302
#endif
303
304
case AUX_FUNC::FLAP:
305
case AUX_FUNC::FBWA_TAILDRAGGER:
306
case AUX_FUNC::AIRBRAKE:
307
break; // input labels, nothing to do
308
309
#if HAL_QUADPLANE_ENABLED
310
case AUX_FUNC::Q_ASSIST:
311
do_aux_function_q_assist_state(ch_flag);
312
break;
313
#endif
314
315
case AUX_FUNC::FWD_THR:
316
break; // VTOL forward throttle input label, nothing to do
317
318
case AUX_FUNC::TER_DISABLE:
319
switch (ch_flag) {
320
case AuxSwitchPos::HIGH:
321
plane.non_auto_terrain_disable = true;
322
if (plane.control_mode->allows_terrain_disable()) {
323
plane.set_target_altitude_current();
324
}
325
break;
326
case AuxSwitchPos::MIDDLE:
327
break;
328
case AuxSwitchPos::LOW:
329
plane.non_auto_terrain_disable = false;
330
if (plane.control_mode->allows_terrain_disable()) {
331
plane.set_target_altitude_current();
332
}
333
break;
334
}
335
gcs().send_text(MAV_SEVERITY_INFO, "NON AUTO TERRN: %s", plane.non_auto_terrain_disable?"OFF":"ON");
336
break;
337
338
case AUX_FUNC::CROW_SELECT:
339
do_aux_function_crow_mode(ch_flag);
340
break;
341
342
#if HAL_QUADPLANE_ENABLED
343
case AUX_FUNC::AIRMODE:
344
switch (ch_flag) {
345
case AuxSwitchPos::HIGH:
346
plane.quadplane.air_mode = AirMode::ON;
347
plane.quadplane.throttle_wait = false;
348
break;
349
case AuxSwitchPos::MIDDLE:
350
break;
351
case AuxSwitchPos::LOW:
352
plane.quadplane.air_mode = AirMode::OFF;
353
break;
354
}
355
break;
356
#endif
357
358
#if AP_AIRSPEED_AUTOCAL_ENABLE
359
case AUX_FUNC::ARSPD_CALIBRATE:
360
switch (ch_flag) {
361
case AuxSwitchPos::HIGH:
362
plane.airspeed.set_calibration_enabled(true);
363
break;
364
case AuxSwitchPos::MIDDLE:
365
break;
366
case AuxSwitchPos::LOW:
367
plane.airspeed.set_calibration_enabled(false);
368
break;
369
}
370
break;
371
#endif
372
373
case AUX_FUNC::LANDING_FLARE:
374
do_aux_function_flare(ch_flag);
375
break;
376
377
#if HAL_PARACHUTE_ENABLED
378
case AUX_FUNC::PARACHUTE_RELEASE:
379
if (ch_flag == AuxSwitchPos::HIGH) {
380
plane.parachute_manual_release();
381
}
382
break;
383
#endif
384
385
case AUX_FUNC::MODE_SWITCH_RESET:
386
rc().reset_mode_switch();
387
break;
388
389
case AUX_FUNC::CRUISE:
390
do_aux_function_change_mode(Mode::Number::CRUISE, ch_flag);
391
break;
392
393
#if HAL_QUADPLANE_ENABLED
394
case AUX_FUNC::ARMDISARM_AIRMODE:
395
RC_Channel::do_aux_function_armdisarm(ch_flag);
396
if (plane.arming.is_armed()) {
397
plane.quadplane.air_mode = AirMode::ON;
398
plane.quadplane.throttle_wait = false;
399
}
400
break;
401
402
case AUX_FUNC::WEATHER_VANE_ENABLE: {
403
if (plane.quadplane.weathervane != nullptr) {
404
switch (ch_flag) {
405
case AuxSwitchPos::HIGH:
406
plane.quadplane.weathervane->allow_weathervaning(true);
407
break;
408
case AuxSwitchPos::MIDDLE:
409
// nothing
410
break;
411
case AuxSwitchPos::LOW:
412
plane.quadplane.weathervane->allow_weathervaning(false);
413
break;
414
}
415
}
416
break;
417
}
418
#endif
419
420
case AUX_FUNC::PLANE_AUTO_LANDING_ABORT:
421
switch(ch_flag) {
422
case AuxSwitchPos::HIGH:
423
IGNORE_RETURN(plane.trigger_land_abort(0));
424
break;
425
case AuxSwitchPos::MIDDLE:
426
case AuxSwitchPos::LOW:
427
break;
428
}
429
break;
430
431
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
432
if (ch_flag == AuxSwitchPos::HIGH) {
433
plane.trim_radio();
434
}
435
break;
436
437
case AUX_FUNC::EMERGENCY_LANDING_EN:
438
switch (ch_flag) {
439
case AuxSwitchPos::HIGH:
440
plane.emergency_landing = true;
441
break;
442
case AuxSwitchPos::MIDDLE:
443
break;
444
case AuxSwitchPos::LOW:
445
plane.emergency_landing = false;
446
break;
447
}
448
break;
449
450
case AUX_FUNC::FW_AUTOTUNE:
451
if (ch_flag == AuxSwitchPos::HIGH && plane.control_mode->mode_allows_autotuning()) {
452
plane.autotune_enable(true);
453
} else if (ch_flag == AuxSwitchPos::HIGH) {
454
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Autotuning not allowed in this mode!");
455
} else {
456
plane.autotune_enable(false);
457
}
458
break;
459
460
case AUX_FUNC::PRECISION_LOITER:
461
// handled by lua scripting, just ignore here
462
break;
463
464
#if QAUTOTUNE_ENABLED
465
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
466
plane.quadplane.qautotune.do_aux_function(ch_flag);
467
break;
468
#endif
469
470
#if AP_QUICKTUNE_ENABLED
471
case AUX_FUNC::QUICKTUNE:
472
plane.quicktune.update_switch_pos(ch_flag);
473
break;
474
#endif
475
476
#if AP_PLANE_SYSTEMID_ENABLED
477
case AUX_FUNC::SYSTEMID:
478
if (ch_flag == AuxSwitchPos::HIGH) {
479
plane.g2.systemid.start();
480
} else if (ch_flag == AuxSwitchPos::LOW) {
481
plane.g2.systemid.stop();
482
}
483
break;
484
#endif
485
486
#if AP_ICENGINE_ENABLED
487
case AUX_FUNC::ICE_START_STOP:
488
plane.g2.ice_control.do_aux_function(trigger);
489
break;
490
#endif
491
492
#if MODE_AUTOLAND_ENABLED
493
case AUX_FUNC::AUTOLAND:
494
do_aux_function_change_mode(Mode::Number::AUTOLAND, ch_flag);
495
break;
496
497
#endif
498
499
default:
500
return RC_Channel::do_aux_function(trigger);
501
}
502
503
return true;
504
}
505
506