Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/RC_Channel_Copter.cpp
9315 views
1
#include "Copter.h"
2
3
#include "RC_Channel_Copter.h"
4
5
6
// defining these two macros and including the RC_Channels_VarInfo header defines the parameter information common to all vehicle types
7
#define RC_CHANNELS_SUBCLASS RC_Channels_Copter
8
#define RC_CHANNEL_SUBCLASS RC_Channel_Copter
9
10
#include <RC_Channel/RC_Channels_VarInfo.h>
11
12
int8_t RC_Channels_Copter::flight_mode_channel_number() const
13
{
14
return copter.g.flight_mode_chan.get();
15
}
16
17
void RC_Channel_Copter::mode_switch_changed(modeswitch_pos_t new_pos)
18
{
19
if (new_pos < 0 || (uint8_t)new_pos > copter.num_flight_modes) {
20
// should not have been called
21
return;
22
}
23
24
if (!copter.set_mode((Mode::Number)copter.flight_modes[new_pos].get(), ModeReason::RC_COMMAND)) {
25
return;
26
}
27
28
if (!rc().find_channel_for_option(AUX_FUNC::SIMPLE_MODE) &&
29
!rc().find_channel_for_option(AUX_FUNC::SUPERSIMPLE_MODE)) {
30
// if none of the Aux Switches are set to Simple or Super Simple Mode then
31
// set Simple Mode using stored parameters from EEPROM
32
if (BIT_IS_SET(copter.g.super_simple, new_pos)) {
33
copter.set_simple_mode(Copter::SimpleMode::SUPERSIMPLE);
34
} else {
35
copter.set_simple_mode(BIT_IS_SET(copter.g.simple_modes, new_pos) ? Copter::SimpleMode::SIMPLE : Copter::SimpleMode::NONE);
36
}
37
}
38
}
39
40
bool RC_Channels_Copter::in_rc_failsafe() const
41
{
42
return copter.failsafe.radio;
43
}
44
45
bool RC_Channels_Copter::has_valid_input() const
46
{
47
if (in_rc_failsafe()) {
48
return false;
49
}
50
if (copter.failsafe.radio_counter != 0) {
51
return false;
52
}
53
return RC_Channels::has_valid_input();
54
}
55
56
// returns true if throttle arming checks should be run
57
bool RC_Channels_Copter::arming_check_throttle() const {
58
if ((copter.g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0) {
59
// center sprung throttle configured, dont run AP_Arming check
60
// Copter already checks this case in its own arming checks
61
return false;
62
}
63
return RC_Channels::arming_check_throttle();
64
}
65
66
RC_Channel * RC_Channels_Copter::get_arming_channel(void) const
67
{
68
return copter.channel_yaw;
69
}
70
71
// init_aux_switch_function - initialize aux functions
72
void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
73
{
74
// init channel options
75
switch(ch_option) {
76
// the following functions do not need to be initialised:
77
case AUX_FUNC::ALTHOLD:
78
case AUX_FUNC::AUTO:
79
case AUX_FUNC::AUTOTUNE_MODE:
80
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
81
case AUX_FUNC::BRAKE:
82
case AUX_FUNC::CIRCLE:
83
case AUX_FUNC::DRIFT:
84
case AUX_FUNC::FLIP:
85
case AUX_FUNC::FLOWHOLD:
86
case AUX_FUNC::FOLLOW:
87
case AUX_FUNC::GUIDED:
88
case AUX_FUNC::LAND:
89
case AUX_FUNC::LOITER:
90
#if HAL_PARACHUTE_ENABLED
91
case AUX_FUNC::PARACHUTE_RELEASE:
92
#endif
93
case AUX_FUNC::POSHOLD:
94
case AUX_FUNC::RESETTOARMEDYAW:
95
case AUX_FUNC::RTL:
96
case AUX_FUNC::SAVE_TRIM:
97
case AUX_FUNC::SAVE_WP:
98
case AUX_FUNC::SMART_RTL:
99
case AUX_FUNC::STABILIZE:
100
case AUX_FUNC::THROW:
101
case AUX_FUNC::USER_FUNC1:
102
case AUX_FUNC::USER_FUNC2:
103
case AUX_FUNC::USER_FUNC3:
104
#if AP_WINCH_ENABLED
105
case AUX_FUNC::WINCH_CONTROL:
106
#endif
107
case AUX_FUNC::ZIGZAG:
108
case AUX_FUNC::ZIGZAG_Auto:
109
case AUX_FUNC::ZIGZAG_SaveWP:
110
case AUX_FUNC::ACRO:
111
case AUX_FUNC::AUTO_RTL:
112
case AUX_FUNC::TURTLE:
113
case AUX_FUNC::SIMPLE_HEADING_RESET:
114
case AUX_FUNC::ARMDISARM_AIRMODE:
115
case AUX_FUNC::TURBINE_START:
116
case AUX_FUNC::FLIGHTMODE_PAUSE:
117
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
118
case AUX_FUNC::AHRS_AUTO_TRIM:
119
#endif
120
break;
121
case AUX_FUNC::ACRO_TRAINER:
122
case AUX_FUNC::ATTCON_ACCEL_LIM:
123
case AUX_FUNC::ATTCON_FEEDFWD:
124
case AUX_FUNC::INVERTED:
125
case AUX_FUNC::MOTOR_INTERLOCK:
126
#if HAL_PARACHUTE_ENABLED
127
case AUX_FUNC::PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
128
case AUX_FUNC::PARACHUTE_ENABLE:
129
#endif
130
case AUX_FUNC::PRECISION_LOITER:
131
#if AP_RANGEFINDER_ENABLED
132
case AUX_FUNC::RANGEFINDER:
133
#endif
134
case AUX_FUNC::SIMPLE_MODE:
135
case AUX_FUNC::STANDBY:
136
case AUX_FUNC::SUPERSIMPLE_MODE:
137
case AUX_FUNC::SURFACE_TRACKING:
138
#if AP_WINCH_ENABLED
139
case AUX_FUNC::WINCH_ENABLE:
140
#endif
141
case AUX_FUNC::AIRMODE:
142
case AUX_FUNC::FORCEFLYING:
143
case AUX_FUNC::CUSTOM_CONTROLLER:
144
case AUX_FUNC::WEATHER_VANE_ENABLE:
145
#if AP_RC_TRANSMITTER_TUNING_ENABLED
146
case AUX_FUNC::TRANSMITTER_TUNING:
147
case AUX_FUNC::TRANSMITTER_TUNING2:
148
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT, ch_in);
149
break;
150
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
151
default:
152
RC_Channel::init_aux_function(ch_option, ch_flag);
153
break;
154
}
155
}
156
157
// do_aux_function_change_mode - change mode based on an aux switch
158
// being moved
159
void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
160
const AuxSwitchPos ch_flag)
161
{
162
switch(ch_flag) {
163
case AuxSwitchPos::HIGH: {
164
// engage mode (if not possible we remain in current flight mode)
165
copter.set_mode(mode, ModeReason::AUX_FUNCTION);
166
break;
167
}
168
default:
169
// return to flight mode switch's flight mode if we are currently
170
// in this mode
171
if (copter.flightmode->mode_number() == mode) {
172
rc().reset_mode_switch();
173
}
174
}
175
}
176
177
// do_aux_function - implement the function invoked by auxiliary switches
178
bool RC_Channel_Copter::do_aux_function(const AuxFuncTrigger &trigger)
179
{
180
const AUX_FUNC &ch_option = trigger.func;
181
const AuxSwitchPos &ch_flag = trigger.pos;
182
183
switch(ch_option) {
184
case AUX_FUNC::FLIP:
185
// flip if switch is on, positive throttle and we're actually flying
186
if (ch_flag == AuxSwitchPos::HIGH) {
187
copter.set_mode(Mode::Number::FLIP, ModeReason::AUX_FUNCTION);
188
}
189
break;
190
191
case AUX_FUNC::SIMPLE_MODE:
192
// low = simple mode off, middle or high position turns simple mode on
193
copter.set_simple_mode((ch_flag == AuxSwitchPos::LOW) ? Copter::SimpleMode::NONE : Copter::SimpleMode::SIMPLE);
194
break;
195
196
case AUX_FUNC::SUPERSIMPLE_MODE: {
197
Copter::SimpleMode newmode = Copter::SimpleMode::NONE;
198
switch (ch_flag) {
199
case AuxSwitchPos::LOW:
200
break;
201
case AuxSwitchPos::MIDDLE:
202
newmode = Copter::SimpleMode::SIMPLE;
203
break;
204
case AuxSwitchPos::HIGH:
205
newmode = Copter::SimpleMode::SUPERSIMPLE;
206
break;
207
}
208
copter.set_simple_mode(newmode);
209
break;
210
}
211
212
#if MODE_RTL_ENABLED
213
case AUX_FUNC::RTL:
214
do_aux_function_change_mode(Mode::Number::RTL, ch_flag);
215
break;
216
#endif
217
218
case AUX_FUNC::SAVE_TRIM:
219
if ((ch_flag == AuxSwitchPos::HIGH) &&
220
(copter.flightmode->allows_save_trim()) &&
221
(copter.channel_throttle->get_control_in() == 0)) {
222
copter.g2.rc_channels.save_trim();
223
}
224
break;
225
226
#if MODE_AUTO_ENABLED
227
case AUX_FUNC::SAVE_WP:
228
// save waypoint when switch is brought high
229
if (ch_flag == RC_Channel::AuxSwitchPos::HIGH) {
230
231
// do not allow saving new waypoints while we're in auto or disarmed
232
if (copter.flightmode == &copter.mode_auto || !copter.motors->armed()) {
233
break;
234
}
235
236
// do not allow saving the first waypoint with zero throttle
237
if (!copter.mode_auto.mission.present() && (copter.channel_throttle->get_control_in() == 0)) {
238
break;
239
}
240
241
// create new mission command
242
AP_Mission::Mission_Command cmd = {};
243
244
// if the mission is empty save a takeoff command
245
if (!copter.mode_auto.mission.present()) {
246
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
247
cmd.id = MAV_CMD_NAV_TAKEOFF;
248
cmd.content.location.alt = MAX(copter.current_loc.alt,100);
249
250
// use the current altitude for the target alt for takeoff.
251
// only altitude will matter to the AP mission script for takeoff.
252
if (copter.mode_auto.mission.add_cmd(cmd)) {
253
// log event
254
LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP);
255
}
256
}
257
258
// set new waypoint to current location
259
cmd.content.location = copter.current_loc;
260
261
// if throttle is above zero, create waypoint command
262
if (copter.channel_throttle->get_control_in() > 0) {
263
cmd.id = MAV_CMD_NAV_WAYPOINT;
264
} else {
265
// with zero throttle, create LAND command
266
cmd.id = MAV_CMD_NAV_LAND;
267
}
268
269
// save command
270
if (copter.mode_auto.mission.add_cmd(cmd)) {
271
// log event
272
LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP);
273
}
274
}
275
break;
276
277
case AUX_FUNC::AUTO:
278
do_aux_function_change_mode(Mode::Number::AUTO, ch_flag);
279
break;
280
#endif
281
282
#if AP_RANGEFINDER_ENABLED
283
case AUX_FUNC::RANGEFINDER:
284
// enable or disable the rangefinder
285
if ((ch_flag == AuxSwitchPos::HIGH) &&
286
copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
287
copter.rangefinder_state.enabled = true;
288
} else {
289
copter.rangefinder_state.enabled = false;
290
}
291
break;
292
#endif // AP_RANGEFINDER_ENABLED
293
294
#if MODE_ACRO_ENABLED
295
case AUX_FUNC::ACRO_TRAINER:
296
switch(ch_flag) {
297
case AuxSwitchPos::LOW:
298
copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::OFF);
299
LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_OFF);
300
break;
301
case AuxSwitchPos::MIDDLE:
302
copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LEVELING);
303
LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_LEVELING);
304
break;
305
case AuxSwitchPos::HIGH:
306
copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LIMITED);
307
LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_LIMITED);
308
break;
309
}
310
break;
311
#endif
312
313
#if AUTOTUNE_ENABLED
314
case AUX_FUNC::AUTOTUNE_MODE:
315
do_aux_function_change_mode(Mode::Number::AUTOTUNE, ch_flag);
316
break;
317
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
318
copter.mode_autotune.autotune.do_aux_function(ch_flag);
319
break;
320
#endif
321
322
case AUX_FUNC::LAND:
323
do_aux_function_change_mode(Mode::Number::LAND, ch_flag);
324
break;
325
326
case AUX_FUNC::GUIDED:
327
do_aux_function_change_mode(Mode::Number::GUIDED, ch_flag);
328
break;
329
330
case AUX_FUNC::LOITER:
331
do_aux_function_change_mode(Mode::Number::LOITER, ch_flag);
332
break;
333
334
case AUX_FUNC::FOLLOW:
335
do_aux_function_change_mode(Mode::Number::FOLLOW, ch_flag);
336
break;
337
338
#if HAL_PARACHUTE_ENABLED
339
case AUX_FUNC::PARACHUTE_ENABLE:
340
// Parachute enable/disable
341
copter.parachute.enabled(ch_flag == AuxSwitchPos::HIGH);
342
break;
343
344
case AUX_FUNC::PARACHUTE_RELEASE:
345
if (ch_flag == AuxSwitchPos::HIGH) {
346
copter.parachute_manual_release();
347
}
348
break;
349
350
case AUX_FUNC::PARACHUTE_3POS:
351
// Parachute disable, enable, release with 3 position switch
352
switch (ch_flag) {
353
case AuxSwitchPos::LOW:
354
copter.parachute.enabled(false);
355
break;
356
case AuxSwitchPos::MIDDLE:
357
copter.parachute.enabled(true);
358
break;
359
case AuxSwitchPos::HIGH:
360
copter.parachute.enabled(true);
361
copter.parachute_manual_release();
362
break;
363
}
364
break;
365
#endif // HAL_PARACHUTE_ENABLED
366
367
case AUX_FUNC::ATTCON_FEEDFWD:
368
// enable or disable feed forward
369
copter.attitude_control->bf_feedforward(ch_flag == AuxSwitchPos::HIGH);
370
break;
371
372
case AUX_FUNC::ATTCON_ACCEL_LIM:
373
// enable or disable accel limiting by restoring defaults
374
copter.attitude_control->accel_limiting(ch_flag == AuxSwitchPos::HIGH);
375
break;
376
377
case AUX_FUNC::MOTOR_INTERLOCK:
378
#if FRAME_CONFIG == HELI_FRAME
379
// The interlock logic for ROTOR_CONTROL_MODE_PASSTHROUGH is handled
380
// in heli_update_rotor_speed_targets. Otherwise turn on when above low.
381
if (copter.motors->get_rsc_mode() != ROTOR_CONTROL_MODE_PASSTHROUGH) {
382
copter.ap.motor_interlock_switch = (ch_flag == AuxSwitchPos::HIGH || ch_flag == AuxSwitchPos::MIDDLE);
383
}
384
#else
385
copter.ap.motor_interlock_switch = (ch_flag == AuxSwitchPos::HIGH || ch_flag == AuxSwitchPos::MIDDLE);
386
#endif
387
break;
388
389
#if FRAME_CONFIG == HELI_FRAME
390
case AUX_FUNC::TURBINE_START:
391
switch (ch_flag) {
392
case AuxSwitchPos::HIGH:
393
copter.motors->set_turb_start(true);
394
break;
395
case AuxSwitchPos::MIDDLE:
396
// nothing
397
break;
398
case AuxSwitchPos::LOW:
399
copter.motors->set_turb_start(false);
400
break;
401
}
402
break;
403
#endif
404
405
#if MODE_BRAKE_ENABLED
406
case AUX_FUNC::BRAKE:
407
do_aux_function_change_mode(Mode::Number::BRAKE, ch_flag);
408
break;
409
#endif
410
411
#if MODE_THROW_ENABLED
412
case AUX_FUNC::THROW:
413
do_aux_function_change_mode(Mode::Number::THROW, ch_flag);
414
break;
415
#endif
416
417
#if AC_PRECLAND_ENABLED && MODE_LOITER_ENABLED
418
case AUX_FUNC::PRECISION_LOITER:
419
switch (ch_flag) {
420
case AuxSwitchPos::HIGH:
421
copter.mode_loiter.set_precision_loiter_enabled(true);
422
break;
423
case AuxSwitchPos::MIDDLE:
424
// nothing
425
break;
426
case AuxSwitchPos::LOW:
427
copter.mode_loiter.set_precision_loiter_enabled(false);
428
break;
429
}
430
break;
431
#endif
432
433
#if MODE_SMARTRTL_ENABLED
434
case AUX_FUNC::SMART_RTL:
435
do_aux_function_change_mode(Mode::Number::SMART_RTL, ch_flag);
436
break;
437
#endif
438
439
#if FRAME_CONFIG == HELI_FRAME
440
case AUX_FUNC::INVERTED:
441
switch (ch_flag) {
442
case AuxSwitchPos::HIGH:
443
if (copter.flightmode->allows_inverted()) {
444
copter.attitude_control->set_inverted_flight(true);
445
} else {
446
gcs().send_text(MAV_SEVERITY_WARNING, "Inverted flight not available in %s mode", copter.flightmode->name());
447
}
448
break;
449
case AuxSwitchPos::MIDDLE:
450
// nothing
451
break;
452
case AuxSwitchPos::LOW:
453
copter.attitude_control->set_inverted_flight(false);
454
break;
455
}
456
break;
457
#endif
458
459
#if AP_WINCH_ENABLED
460
case AUX_FUNC::WINCH_ENABLE:
461
switch (ch_flag) {
462
case AuxSwitchPos::HIGH:
463
// high switch position stops winch using rate control
464
copter.g2.winch.set_desired_rate(0.0f);
465
break;
466
case AuxSwitchPos::MIDDLE:
467
case AuxSwitchPos::LOW:
468
// all other position relax winch
469
copter.g2.winch.relax();
470
break;
471
}
472
break;
473
474
case AUX_FUNC::WINCH_CONTROL:
475
// do nothing, used to control the rate of the winch and is processed within AP_Winch
476
break;
477
#endif // AP_WINCH_ENABLED
478
479
#ifdef USERHOOK_AUXSWITCH
480
case AUX_FUNC::USER_FUNC1:
481
copter.userhook_auxSwitch1(ch_flag);
482
break;
483
484
case AUX_FUNC::USER_FUNC2:
485
copter.userhook_auxSwitch2(ch_flag);
486
break;
487
488
case AUX_FUNC::USER_FUNC3:
489
copter.userhook_auxSwitch3(ch_flag);
490
break;
491
#endif
492
493
#if MODE_ZIGZAG_ENABLED
494
case AUX_FUNC::ZIGZAG:
495
do_aux_function_change_mode(Mode::Number::ZIGZAG, ch_flag);
496
break;
497
498
case AUX_FUNC::ZIGZAG_SaveWP:
499
if (copter.flightmode == &copter.mode_zigzag) {
500
// initialize zigzag auto
501
copter.mode_zigzag.init_auto();
502
switch (ch_flag) {
503
case AuxSwitchPos::LOW:
504
copter.mode_zigzag.save_or_move_to_destination(ModeZigZag::Destination::A);
505
break;
506
case AuxSwitchPos::MIDDLE:
507
copter.mode_zigzag.return_to_manual_control(false);
508
break;
509
case AuxSwitchPos::HIGH:
510
copter.mode_zigzag.save_or_move_to_destination(ModeZigZag::Destination::B);
511
break;
512
}
513
}
514
break;
515
#endif
516
517
case AUX_FUNC::STABILIZE:
518
do_aux_function_change_mode(Mode::Number::STABILIZE, ch_flag);
519
break;
520
521
#if MODE_POSHOLD_ENABLED
522
case AUX_FUNC::POSHOLD:
523
do_aux_function_change_mode(Mode::Number::POSHOLD, ch_flag);
524
break;
525
#endif
526
527
case AUX_FUNC::ALTHOLD:
528
do_aux_function_change_mode(Mode::Number::ALT_HOLD, ch_flag);
529
break;
530
531
#if MODE_ACRO_ENABLED
532
case AUX_FUNC::ACRO:
533
do_aux_function_change_mode(Mode::Number::ACRO, ch_flag);
534
break;
535
#endif
536
537
#if MODE_FLOWHOLD_ENABLED
538
case AUX_FUNC::FLOWHOLD:
539
do_aux_function_change_mode(Mode::Number::FLOWHOLD, ch_flag);
540
break;
541
#endif
542
543
#if MODE_CIRCLE_ENABLED
544
case AUX_FUNC::CIRCLE:
545
do_aux_function_change_mode(Mode::Number::CIRCLE, ch_flag);
546
break;
547
#endif
548
549
#if MODE_DRIFT_ENABLED
550
case AUX_FUNC::DRIFT:
551
do_aux_function_change_mode(Mode::Number::DRIFT, ch_flag);
552
break;
553
#endif
554
555
case AUX_FUNC::STANDBY: {
556
switch (ch_flag) {
557
case AuxSwitchPos::HIGH:
558
copter.standby_active = true;
559
LOGGER_WRITE_EVENT(LogEvent::STANDBY_ENABLE);
560
gcs().send_text(MAV_SEVERITY_INFO, "Stand By Enabled");
561
break;
562
default:
563
copter.standby_active = false;
564
LOGGER_WRITE_EVENT(LogEvent::STANDBY_DISABLE);
565
gcs().send_text(MAV_SEVERITY_INFO, "Stand By Disabled");
566
break;
567
}
568
break;
569
}
570
571
#if AP_RANGEFINDER_ENABLED
572
case AUX_FUNC::SURFACE_TRACKING:
573
switch (ch_flag) {
574
case AuxSwitchPos::LOW:
575
copter.surface_tracking.set_surface(Copter::SurfaceTracking::Surface::GROUND);
576
break;
577
case AuxSwitchPos::MIDDLE:
578
copter.surface_tracking.set_surface(Copter::SurfaceTracking::Surface::NONE);
579
break;
580
case AuxSwitchPos::HIGH:
581
copter.surface_tracking.set_surface(Copter::SurfaceTracking::Surface::CEILING);
582
break;
583
}
584
break;
585
#endif
586
587
case AUX_FUNC::FLIGHTMODE_PAUSE:
588
switch (ch_flag) {
589
case AuxSwitchPos::HIGH:
590
if (!copter.flightmode->pause()) {
591
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Flight Mode Pause failed");
592
}
593
break;
594
case AuxSwitchPos::MIDDLE:
595
break;
596
case AuxSwitchPos::LOW:
597
copter.flightmode->resume();
598
break;
599
}
600
break;
601
602
#if MODE_ZIGZAG_ENABLED
603
case AUX_FUNC::ZIGZAG_Auto:
604
if (copter.flightmode == &copter.mode_zigzag) {
605
switch (ch_flag) {
606
case AuxSwitchPos::HIGH:
607
copter.mode_zigzag.run_auto();
608
break;
609
default:
610
copter.mode_zigzag.suspend_auto();
611
break;
612
}
613
}
614
break;
615
#endif
616
617
case AUX_FUNC::AIRMODE:
618
do_aux_function_change_air_mode(ch_flag);
619
#if MODE_ACRO_ENABLED && FRAME_CONFIG != HELI_FRAME
620
copter.mode_acro.air_mode_aux_changed();
621
#endif
622
break;
623
624
case AUX_FUNC::FORCEFLYING:
625
do_aux_function_change_force_flying(ch_flag);
626
break;
627
628
#if MODE_AUTO_ENABLED
629
case AUX_FUNC::AUTO_RTL:
630
do_aux_function_change_mode(Mode::Number::AUTO_RTL, ch_flag);
631
break;
632
#endif
633
634
#if MODE_TURTLE_ENABLED
635
case AUX_FUNC::TURTLE:
636
do_aux_function_change_mode(Mode::Number::TURTLE, ch_flag);
637
break;
638
#endif
639
640
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
641
case AUX_FUNC::AHRS_AUTO_TRIM:
642
copter.g2.rc_channels.do_aux_function_ahrs_auto_trim(ch_flag);
643
break;
644
#endif // AP_COPTER_AHRS_AUTO_TRIM_ENABLED
645
646
case AUX_FUNC::SIMPLE_HEADING_RESET:
647
if (ch_flag == AuxSwitchPos::HIGH) {
648
copter.init_simple_bearing();
649
gcs().send_text(MAV_SEVERITY_INFO, "Simple heading reset");
650
}
651
break;
652
653
case AUX_FUNC::ARMDISARM_AIRMODE:
654
RC_Channel::do_aux_function_armdisarm(ch_flag);
655
if (copter.arming.is_armed()) {
656
copter.ap.armed_with_airmode_switch = true;
657
}
658
break;
659
660
#if AC_CUSTOMCONTROL_MULTI_ENABLED
661
case AUX_FUNC::CUSTOM_CONTROLLER:
662
copter.custom_control.set_custom_controller(ch_flag == AuxSwitchPos::HIGH);
663
break;
664
#endif
665
666
#if WEATHERVANE_ENABLED
667
case AUX_FUNC::WEATHER_VANE_ENABLE: {
668
switch (ch_flag) {
669
case AuxSwitchPos::HIGH:
670
copter.g2.weathervane.allow_weathervaning(true);
671
break;
672
case AuxSwitchPos::MIDDLE:
673
break;
674
case AuxSwitchPos::LOW:
675
copter.g2.weathervane.allow_weathervaning(false);
676
break;
677
}
678
break;
679
}
680
#endif
681
#if AP_RC_TRANSMITTER_TUNING_ENABLED
682
case AUX_FUNC::TRANSMITTER_TUNING:
683
case AUX_FUNC::TRANSMITTER_TUNING2:
684
// do nothing, used in tuning.cpp for transmitter based tuning
685
break;
686
#endif // AP_RC_TRANSMITTER_TUNING_ENABLED
687
688
default:
689
return RC_Channel::do_aux_function(trigger);
690
}
691
return true;
692
}
693
694
// change air-mode status
695
void RC_Channel_Copter::do_aux_function_change_air_mode(const AuxSwitchPos ch_flag)
696
{
697
switch (ch_flag) {
698
case AuxSwitchPos::HIGH:
699
copter.air_mode = AirMode::AIRMODE_ENABLED;
700
break;
701
case AuxSwitchPos::MIDDLE:
702
break;
703
case AuxSwitchPos::LOW:
704
copter.air_mode = AirMode::AIRMODE_DISABLED;
705
break;
706
}
707
}
708
709
// change force flying status
710
void RC_Channel_Copter::do_aux_function_change_force_flying(const AuxSwitchPos ch_flag)
711
{
712
switch (ch_flag) {
713
case AuxSwitchPos::HIGH:
714
copter.force_flying = true;
715
break;
716
case AuxSwitchPos::MIDDLE:
717
break;
718
case AuxSwitchPos::LOW:
719
copter.force_flying = false;
720
break;
721
}
722
}
723
724
// note that this is a method on the RC_Channels object, not the
725
// individual channel
726
// save_trim - adds roll and pitch trims from the radio to ahrs
727
void RC_Channels_Copter::save_trim()
728
{
729
float roll_trim = 0;
730
float pitch_trim = 0;
731
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
732
if (auto_trim.running) {
733
auto_trim.running = false;
734
} else {
735
#endif
736
// save roll and pitch trim
737
roll_trim = cd_to_rad((float)get_roll_channel().get_control_in());
738
pitch_trim = cd_to_rad((float)get_pitch_channel().get_control_in());
739
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
740
}
741
#endif
742
AP::ahrs().add_trim(roll_trim, pitch_trim);
743
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
744
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
745
}
746
747
#if AP_COPTER_AHRS_AUTO_TRIM_ENABLED
748
// start/stop ahrs auto trim
749
void RC_Channels_Copter::do_aux_function_ahrs_auto_trim(const RC_Channel::AuxSwitchPos ch_flag)
750
{
751
switch (ch_flag) {
752
case RC_Channel::AuxSwitchPos::HIGH:
753
if (!copter.flightmode->allows_auto_trim()) {
754
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim not allowed in this mode");
755
break;
756
}
757
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim running");
758
// flash the leds
759
AP_Notify::flags.save_trim = true;
760
auto_trim.running = true;
761
break;
762
case RC_Channel::AuxSwitchPos::MIDDLE:
763
break;
764
case RC_Channel::AuxSwitchPos::LOW:
765
if (auto_trim.running) {
766
AP_Notify::flags.save_trim = false;
767
save_trim();
768
}
769
break;
770
}
771
}
772
773
// auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions
774
// meant to be called continuously while the pilot attempts to keep the copter level
775
void RC_Channels_Copter::auto_trim_cancel()
776
{
777
auto_trim.running = false;
778
AP_Notify::flags.save_trim = false;
779
gcs().send_text(MAV_SEVERITY_INFO, "AutoTrim cancelled");
780
// restore original trims
781
}
782
783
void RC_Channels_Copter::auto_trim_run()
784
{
785
if (!auto_trim.running) {
786
return;
787
}
788
789
// only trim in certain modes:
790
if (!copter.flightmode->allows_auto_trim()) {
791
auto_trim_cancel();
792
return;
793
}
794
795
// must be started and stopped mid-air:
796
if (copter.ap.land_complete_maybe) {
797
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"Must be flying to use AUTOTRIM");
798
auto_trim_cancel();
799
return;
800
}
801
// calculate roll trim adjustment, divisor set subjectively to give same "feel" as previous RC input method
802
float roll_trim_adjustment_rad = copter.attitude_control->get_att_target_euler_rad().x / 20.0f;
803
804
// calculate pitch trim adjustment, divisor set subjectively to give same "feel" as previous RC input method
805
float pitch_trim_adjustment_rad = copter.attitude_control->get_att_target_euler_rad().y / 20.0f;
806
807
// add trim to ahrs object, but do not save to permanent storage:
808
AP::ahrs().add_trim(roll_trim_adjustment_rad, pitch_trim_adjustment_rad, false);
809
}
810
811
#endif // AP_COPTER_AHRS_AUTO_TRIM_ENABLED
812
813