APM:Copter
switches.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200
4 
5 //Documentation of Aux Switch Flags:
6 struct {
7  uint8_t CH6_flag : 2; // 0, 1 // ch6 aux switch : 0 is low or false, 1 is center or true, 2 is high
8  uint8_t CH7_flag : 2; // 2, 3 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high
9  uint8_t CH8_flag : 2; // 4, 5 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high
10  uint8_t CH9_flag : 2; // 6, 7 // ch9 aux switch : 0 is low or false, 1 is center or true, 2 is high
11  uint8_t CH10_flag : 2; // 8, 9 // ch10 aux switch : 0 is low or false, 1 is center or true, 2 is high
12  uint8_t CH11_flag : 2; // 10,11 // ch11 aux switch : 0 is low or false, 1 is center or true, 2 is high
13  uint8_t CH12_flag : 2; // 12,13 // ch12 aux switch : 0 is low or false, 1 is center or true, 2 is high
14 } aux_con;
15 
17 {
18  if (g.flight_mode_chan <= 0) {
19  // no flight mode channel
20  return;
21  }
22 
23  uint32_t tnow_ms = millis();
24 
25  // calculate position of flight mode switch
26  int8_t switch_position;
27  uint16_t mode_in = RC_Channels::rc_channel(g.flight_mode_chan-1)->get_radio_in();
28  if (mode_in < 1231) switch_position = 0;
29  else if (mode_in < 1361) switch_position = 1;
30  else if (mode_in < 1491) switch_position = 2;
31  else if (mode_in < 1621) switch_position = 3;
32  else if (mode_in < 1750) switch_position = 4;
33  else switch_position = 5;
34 
35  // store time that switch last moved
36  if (control_switch_state.last_switch_position != switch_position) {
37  control_switch_state.last_edge_time_ms = tnow_ms;
38  }
39 
40  // debounce switch
41  bool control_switch_changed = control_switch_state.debounced_switch_position != switch_position;
42  bool sufficient_time_elapsed = tnow_ms - control_switch_state.last_edge_time_ms > CONTROL_SWITCH_DEBOUNCE_TIME_MS;
43  bool failsafe_disengaged = !failsafe.radio && failsafe.radio_counter == 0;
44 
45  if (control_switch_changed && sufficient_time_elapsed && failsafe_disengaged) {
46  // set flight mode and simple mode setting
47  if (set_mode((control_mode_t)flight_modes[switch_position].get(), MODE_REASON_TX_COMMAND)) {
48  // play a tone
49  if (control_switch_state.debounced_switch_position != -1) {
50  // alert user to mode change failure (except if autopilot is just starting up)
51  if (ap.initialised) {
53  }
54  }
55 
56  if (!check_if_auxsw_mode_used(AUXSW_SIMPLE_MODE) && !check_if_auxsw_mode_used(AUXSW_SUPERSIMPLE_MODE)) {
57  // if none of the Aux Switches are set to Simple or Super Simple Mode then
58  // set Simple Mode using stored parameters from EEPROM
59  if (BIT_IS_SET(g.super_simple, switch_position)) {
60  set_simple_mode(2);
61  } else {
62  set_simple_mode(BIT_IS_SET(g.simple_modes, switch_position));
63  }
64  }
65 
66  } else if (control_switch_state.last_switch_position != -1) {
67  // alert user to mode change failure
69  }
70 
71  // set the debounced switch position
72  control_switch_state.debounced_switch_position = switch_position;
73  }
74 
75  control_switch_state.last_switch_position = switch_position;
76 }
77 
78 // check_if_auxsw_mode_used - Check to see if any of the Aux Switches are set to a given mode.
79 bool Copter::check_if_auxsw_mode_used(uint8_t auxsw_mode_check)
80 {
81  bool ret = g.ch7_option == auxsw_mode_check || g.ch8_option == auxsw_mode_check || g.ch9_option == auxsw_mode_check
82  || g.ch10_option == auxsw_mode_check || g.ch11_option == auxsw_mode_check || g.ch12_option == auxsw_mode_check;
83 
84  return ret;
85 }
86 
87 // check_duplicate_auxsw - Check to see if any Aux Switch Functions are duplicated
89 {
90  uint8_t auxsw_option_counts[AUXSW_SWITCH_MAX] = {};
91  auxsw_option_counts[g.ch7_option]++;
92  auxsw_option_counts[g.ch8_option]++;
93  auxsw_option_counts[g.ch9_option]++;
94  auxsw_option_counts[g.ch10_option]++;
95  auxsw_option_counts[g.ch11_option]++;
96  auxsw_option_counts[g.ch12_option]++;
97 
98  for (uint8_t i=0; i<sizeof(auxsw_option_counts); i++) {
99  if (i == AUXSW_DO_NOTHING) {
100  continue;
101  }
102  if (auxsw_option_counts[i] > 1) {
103  return true;
104  }
105  }
106  return false;
107 }
108 
110 {
111  control_switch_state.last_switch_position = control_switch_state.debounced_switch_position = -1;
112  read_control_switch();
113 }
114 
115 // read_3pos_switch
116 uint8_t Copter::read_3pos_switch(uint8_t chan)
117 {
118  uint16_t radio_in = RC_Channels::rc_channel(chan)->get_radio_in();
119  if (radio_in < AUX_SWITCH_PWM_TRIGGER_LOW) return AUX_SWITCH_LOW; // switch is in low position
120  if (radio_in > AUX_SWITCH_PWM_TRIGGER_HIGH) return AUX_SWITCH_HIGH; // switch is in high position
121  return AUX_SWITCH_MIDDLE; // switch is in middle position
122 }
123 
124 // can't take reference to a bitfield member, thus a #define:
125 #define read_aux_switch(chan, flag, option) \
126  do { \
127  switch_position = read_3pos_switch(chan); \
128  if (debounce_aux_switch(chan, flag) && flag != switch_position) { \
129  flag = switch_position; \
130  do_aux_switch_function(option, flag); \
131  } \
132  } while (false)
133 
134 // read_aux_switches - checks aux switch positions and invokes configured actions
136 {
137  uint8_t switch_position;
138 
139  // exit immediately during radio failsafe
140  if (failsafe.radio || failsafe.radio_counter != 0) {
141  return;
142  }
143 
144  read_aux_switch(CH_7, aux_con.CH7_flag, g.ch7_option);
145  read_aux_switch(CH_8, aux_con.CH8_flag, g.ch8_option);
146  read_aux_switch(CH_9, aux_con.CH9_flag, g.ch9_option);
147  read_aux_switch(CH_10, aux_con.CH10_flag, g.ch10_option);
148  read_aux_switch(CH_11, aux_con.CH11_flag, g.ch11_option);
149 
150 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
151  read_aux_switch(CH_12, aux_con.CH12_flag, g.ch12_option);
152 #endif
153 }
154 
155 #undef read_aux_switch
156 
157 // init_aux_switches - invoke configured actions at start-up for aux function where it is safe to do so
159 {
160  // set the CH7 ~ CH12 flags
161  aux_con.CH7_flag = read_3pos_switch(CH_7);
162  aux_con.CH8_flag = read_3pos_switch(CH_8);
163  aux_con.CH10_flag = read_3pos_switch(CH_10);
164  aux_con.CH11_flag = read_3pos_switch(CH_11);
165 
166  // ch9, ch12 only supported on some boards
167  aux_con.CH9_flag = read_3pos_switch(CH_9);
168  aux_con.CH12_flag = read_3pos_switch(CH_12);
169 
170  // initialise functions assigned to switches
171  init_aux_switch_function(g.ch7_option, aux_con.CH7_flag);
172  init_aux_switch_function(g.ch8_option, aux_con.CH8_flag);
173  init_aux_switch_function(g.ch10_option, aux_con.CH10_flag);
174  init_aux_switch_function(g.ch11_option, aux_con.CH11_flag);
175 
176  // ch9, ch12 only supported on some boards
177  init_aux_switch_function(g.ch9_option, aux_con.CH9_flag);
178  init_aux_switch_function(g.ch12_option, aux_con.CH12_flag);
179 }
180 
181 // init_aux_switch_function - initialize aux functions
182 void Copter::init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
183 {
184  // init channel options
185  switch(ch_option) {
186  case AUXSW_SIMPLE_MODE:
187  case AUXSW_RANGEFINDER:
188  case AUXSW_FENCE:
190  case AUXSW_ACRO_TRAINER:
191  case AUXSW_GRIPPER:
192  case AUXSW_SPRAYER:
194  case AUXSW_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
195  case AUXSW_RETRACT_MOUNT:
196  case AUXSW_MISSION_RESET:
199  case AUXSW_MOTOR_ESTOP:
201  case AUXSW_AVOID_ADSB:
204  case AUXSW_INVERTED:
205  case AUXSW_WINCH_ENABLE:
207  do_aux_switch_function(ch_option, ch_flag);
208  break;
209  }
210 }
211 
212 /*
213  debounce an aux switch using a counter in copter.debounce
214  structure. This will return false until the same ch_flag is seen debounce_count times
215  */
216 bool Copter::debounce_aux_switch(uint8_t chan, uint8_t ch_flag)
217 {
218  // a value of 2 means we need 3 values in a row with the same
219  // value to activate
220  const uint8_t debounce_count = 2;
221 
222  if (chan < CH_7 || chan > CH_12) {
223  // someone has forgotten to expand the debounce channel range
224  return false;
225  }
226  struct debounce &db = aux_debounce[chan-CH_7];
227  if (db.ch_flag != ch_flag) {
228  db.ch_flag = ch_flag;
229  db.count = 0;
230  return false;
231  }
232  if (db.count < debounce_count) {
233  db.count++;
234  }
235  return db.count >= debounce_count;
236 }
237 
238 // do_aux_switch_function - implement the function invoked by the ch7 or ch8 switch
239 void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
240 {
241 
242  switch(ch_function) {
243  case AUXSW_FLIP:
244  // flip if switch is on, positive throttle and we're actually flying
245  if (ch_flag == AUX_SWITCH_HIGH) {
246  set_mode(FLIP, MODE_REASON_TX_COMMAND);
247  }
248  break;
249 
250  case AUXSW_SIMPLE_MODE:
251  // low = simple mode off, middle or high position turns simple mode on
252  set_simple_mode(ch_flag == AUX_SWITCH_HIGH || ch_flag == AUX_SWITCH_MIDDLE);
253  break;
254 
256  // low = simple mode off, middle = simple mode, high = super simple mode
257  set_simple_mode(ch_flag);
258  break;
259 
260  case AUXSW_RTL:
261 #if MODE_RTL_ENABLED == ENABLED
262  if (ch_flag == AUX_SWITCH_HIGH) {
263  // engage RTL (if not possible we remain in current flight mode)
264  set_mode(RTL, MODE_REASON_TX_COMMAND);
265  } else {
266  // return to flight mode switch's flight mode if we are currently in RTL
267  if (control_mode == RTL) {
268  reset_control_switch();
269  }
270  }
271 #endif
272  break;
273 
274  case AUXSW_SAVE_TRIM:
275  if ((ch_flag == AUX_SWITCH_HIGH) && (control_mode <= ACRO) && (channel_throttle->get_control_in() == 0)) {
276  save_trim();
277  }
278  break;
279 
280  case AUXSW_SAVE_WP:
281 #if MODE_AUTO_ENABLED == ENABLED
282  // save waypoint when switch is brought high
283  if (ch_flag == AUX_SWITCH_HIGH) {
284 
285  // do not allow saving new waypoints while we're in auto or disarmed
286  if (control_mode == AUTO || !motors->armed()) {
287  return;
288  }
289 
290  // do not allow saving the first waypoint with zero throttle
291  if ((mission.num_commands() == 0) && (channel_throttle->get_control_in() == 0)) {
292  return;
293  }
294 
295  // create new mission command
297 
298  // if the mission is empty save a takeoff command
299  if (mission.num_commands() == 0) {
300  // set our location ID to 16, MAV_CMD_NAV_WAYPOINT
301  cmd.id = MAV_CMD_NAV_TAKEOFF;
302  cmd.content.location.options = 0;
303  cmd.p1 = 0;
304  cmd.content.location.lat = 0;
305  cmd.content.location.lng = 0;
306  cmd.content.location.alt = MAX(current_loc.alt,100);
307 
308  // use the current altitude for the target alt for takeoff.
309  // only altitude will matter to the AP mission script for takeoff.
310  if (mission.add_cmd(cmd)) {
311  // log event
312  Log_Write_Event(DATA_SAVEWP_ADD_WP);
313  }
314  }
315 
316  // set new waypoint to current location
317  cmd.content.location = current_loc;
318 
319  // if throttle is above zero, create waypoint command
320  if (channel_throttle->get_control_in() > 0) {
321  cmd.id = MAV_CMD_NAV_WAYPOINT;
322  } else {
323  // with zero throttle, create LAND command
324  cmd.id = MAV_CMD_NAV_LAND;
325  }
326 
327  // save command
328  if (mission.add_cmd(cmd)) {
329  // log event
330  Log_Write_Event(DATA_SAVEWP_ADD_WP);
331  }
332  }
333 #endif
334  break;
335 
336  case AUXSW_MISSION_RESET:
337 #if MODE_AUTO_ENABLED == ENABLED
338  if (ch_flag == AUX_SWITCH_HIGH) {
339  mission.reset();
340  }
341 #endif
342  break;
343 
344  case AUXSW_AUTO:
345 #if MODE_AUTO_ENABLED == ENABLED
346  if (ch_flag == AUX_SWITCH_HIGH) {
347  set_mode(AUTO, MODE_REASON_TX_COMMAND);
348  } else {
349  // return to flight mode switch's flight mode if we are currently in AUTO
350  if (control_mode == AUTO) {
351  reset_control_switch();
352  }
353  }
354 #endif
355  break;
356 
358 #if CAMERA == ENABLED
359  if (ch_flag == AUX_SWITCH_HIGH) {
360  camera.take_picture();
361  }
362 #endif
363  break;
364 
365  case AUXSW_RANGEFINDER:
366  // enable or disable the rangefinder
367 #if RANGEFINDER_ENABLED == ENABLED
368  if ((ch_flag == AUX_SWITCH_HIGH) && rangefinder.has_orientation(ROTATION_PITCH_270)) {
369  rangefinder_state.enabled = true;
370  } else {
371  rangefinder_state.enabled = false;
372  }
373 #endif
374  break;
375 
376  case AUXSW_FENCE:
377 #if AC_FENCE == ENABLED
378  // enable or disable the fence
379  if (ch_flag == AUX_SWITCH_HIGH) {
380  fence.enable(true);
381  Log_Write_Event(DATA_FENCE_ENABLE);
382  } else {
383  fence.enable(false);
384  Log_Write_Event(DATA_FENCE_DISABLE);
385  }
386 #endif
387  break;
388 
389  case AUXSW_ACRO_TRAINER:
390 #if MODE_ACRO_ENABLED == ENABLED
391  switch(ch_flag) {
392  case AUX_SWITCH_LOW:
393  g.acro_trainer = ACRO_TRAINER_DISABLED;
394  Log_Write_Event(DATA_ACRO_TRAINER_DISABLED);
395  break;
396  case AUX_SWITCH_MIDDLE:
397  g.acro_trainer = ACRO_TRAINER_LEVELING;
398  Log_Write_Event(DATA_ACRO_TRAINER_LEVELING);
399  break;
400  case AUX_SWITCH_HIGH:
401  g.acro_trainer = ACRO_TRAINER_LIMITED;
402  Log_Write_Event(DATA_ACRO_TRAINER_LIMITED);
403  break;
404  }
405 #endif
406  break;
407 
408  case AUXSW_GRIPPER:
409 #if GRIPPER_ENABLED == ENABLED
410  switch(ch_flag) {
411  case AUX_SWITCH_LOW:
412  g2.gripper.release();
413  Log_Write_Event(DATA_GRIPPER_RELEASE);
414  break;
415  case AUX_SWITCH_HIGH:
416  g2.gripper.grab();
417  Log_Write_Event(DATA_GRIPPER_GRAB);
418  break;
419  }
420 #endif
421  break;
422 
423  case AUXSW_SPRAYER:
424 #if SPRAYER == ENABLED
425  sprayer.run(ch_flag == AUX_SWITCH_HIGH);
426  // if we are disarmed the pilot must want to test the pump
427  sprayer.test_pump((ch_flag == AUX_SWITCH_HIGH) && !motors->armed());
428 #endif
429  break;
430 
431  case AUXSW_AUTOTUNE:
432 #if AUTOTUNE_ENABLED == ENABLED
433  // turn on auto tuner
434  switch(ch_flag) {
435  case AUX_SWITCH_LOW:
436  case AUX_SWITCH_MIDDLE:
437  // restore flight mode based on flight mode switch position
438  if (control_mode == AUTOTUNE) {
439  reset_control_switch();
440  }
441  break;
442  case AUX_SWITCH_HIGH:
443  // start an autotuning session
444  set_mode(AUTOTUNE, MODE_REASON_TX_COMMAND);
445  break;
446  }
447 #endif
448  break;
449 
450  case AUXSW_LAND:
451  if (ch_flag == AUX_SWITCH_HIGH) {
452  set_mode(LAND, MODE_REASON_TX_COMMAND);
453  } else {
454  // return to flight mode switch's flight mode if we are currently in LAND
455  if (control_mode == LAND) {
456  reset_control_switch();
457  }
458  }
459  break;
460 
462 #if PARACHUTE == ENABLED
463  // Parachute enable/disable
464  parachute.enabled(ch_flag == AUX_SWITCH_HIGH);
465 #endif
466  break;
467 
469 #if PARACHUTE == ENABLED
470  if (ch_flag == AUX_SWITCH_HIGH) {
471  parachute_manual_release();
472  }
473 #endif
474  break;
475 
477 #if PARACHUTE == ENABLED
478  // Parachute disable, enable, release with 3 position switch
479  switch (ch_flag) {
480  case AUX_SWITCH_LOW:
481  parachute.enabled(false);
482  Log_Write_Event(DATA_PARACHUTE_DISABLED);
483  break;
484  case AUX_SWITCH_MIDDLE:
485  parachute.enabled(true);
486  Log_Write_Event(DATA_PARACHUTE_ENABLED);
487  break;
488  case AUX_SWITCH_HIGH:
489  parachute.enabled(true);
490  parachute_manual_release();
491  break;
492  }
493 #endif
494  break;
495 
497  // enable or disable feed forward
498  attitude_control->bf_feedforward(ch_flag == AUX_SWITCH_HIGH);
499  break;
500 
502  // enable or disable accel limiting by restoring defaults
503  attitude_control->accel_limiting(ch_flag == AUX_SWITCH_HIGH);
504  break;
505 
506  case AUXSW_RETRACT_MOUNT:
507 #if MOUNT == ENABLE
508  switch (ch_flag) {
509  case AUX_SWITCH_HIGH:
510  camera_mount.set_mode(MAV_MOUNT_MODE_RETRACT);
511  break;
512  case AUX_SWITCH_LOW:
513  camera_mount.set_mode_to_default();
514  break;
515  }
516 #endif
517  break;
518 
519  case AUXSW_RELAY:
520  ServoRelayEvents.do_set_relay(0, ch_flag == AUX_SWITCH_HIGH);
521  break;
522 
523  case AUXSW_RELAY2:
524  ServoRelayEvents.do_set_relay(1, ch_flag == AUX_SWITCH_HIGH);
525  break;
526 
527  case AUXSW_RELAY3:
528  ServoRelayEvents.do_set_relay(2, ch_flag == AUX_SWITCH_HIGH);
529  break;
530 
531  case AUXSW_RELAY4:
532  ServoRelayEvents.do_set_relay(3, ch_flag == AUX_SWITCH_HIGH);
533  break;
534 
535  case AUXSW_LANDING_GEAR:
536  switch (ch_flag) {
537  case AUX_SWITCH_LOW:
538  landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
539  break;
540  case AUX_SWITCH_HIGH:
541  landinggear.set_position(AP_LandingGear::LandingGear_Retract);
542  break;
543  }
544  break;
545 
547  switch (ch_flag) {
548  case AUX_SWITCH_HIGH:
550  break;
551  case AUX_SWITCH_LOW:
553  break;
554  }
555  break;
556 
557  case AUXSW_MOTOR_ESTOP:
558  // Turn on Emergency Stop logic when channel is high
559  set_motor_emergency_stop(ch_flag == AUX_SWITCH_HIGH);
560  break;
561 
563  // Turn on when above LOW, because channel will also be used for speed
564  // control signal in tradheli
565  ap.motor_interlock_switch = (ch_flag == AUX_SWITCH_HIGH || ch_flag == AUX_SWITCH_MIDDLE);
566  break;
567 
568  case AUXSW_BRAKE:
569 #if MODE_BRAKE_ENABLED == ENABLED
570  // brake flight mode
571  if (ch_flag == AUX_SWITCH_HIGH) {
572  set_mode(BRAKE, MODE_REASON_TX_COMMAND);
573  } else {
574  // return to flight mode switch's flight mode if we are currently in BRAKE
575  if (control_mode == BRAKE) {
576  reset_control_switch();
577  }
578  }
579 #endif
580  break;
581 
582  case AUXSW_THROW:
583 #if MODE_THROW_ENABLED == ENABLED
584  // throw flight mode
585  if (ch_flag == AUX_SWITCH_HIGH) {
586  set_mode(THROW, MODE_REASON_TX_COMMAND);
587  } else {
588  // return to flight mode switch's flight mode if we are currently in throw mode
589  if (control_mode == THROW) {
590  reset_control_switch();
591  }
592  }
593 #endif
594  break;
595 
596  case AUXSW_AVOID_ADSB:
597 #if ADSB_ENABLED == ENABLED
598  // enable or disable AP_Avoidance
599  if (ch_flag == AUX_SWITCH_HIGH) {
600  avoidance_adsb.enable();
601  Log_Write_Event(DATA_AVOIDANCE_ADSB_ENABLE);
602  } else {
603  avoidance_adsb.disable();
604  Log_Write_Event(DATA_AVOIDANCE_ADSB_DISABLE);
605  }
606 #endif
607  break;
608 
610 #if PRECISION_LANDING == ENABLED && MODE_LOITER_ENABLED == ENABLED
611  switch (ch_flag) {
612  case AUX_SWITCH_HIGH:
613  mode_loiter.set_precision_loiter_enabled(true);
614  break;
615  case AUX_SWITCH_LOW:
616  mode_loiter.set_precision_loiter_enabled(false);
617  break;
618  }
619 #endif
620  break;
621 
623 #if PROXIMITY_ENABLED == ENABLED && AC_AVOID_ENABLED == ENABLED
624  switch (ch_flag) {
625  case AUX_SWITCH_HIGH:
626  avoid.proximity_avoidance_enable(true);
627  Log_Write_Event(DATA_AVOIDANCE_PROXIMITY_ENABLE);
628  break;
629  case AUX_SWITCH_LOW:
630  avoid.proximity_avoidance_enable(false);
631  Log_Write_Event(DATA_AVOIDANCE_PROXIMITY_DISABLE);
632  break;
633  }
634 #endif
635  break;
636  case AUXSW_ARMDISARM:
637  // arm or disarm the vehicle
638  switch (ch_flag) {
639  case AUX_SWITCH_HIGH:
640  init_arm_motors(false);
641  // remember that we are using an arming switch, for use by set_throttle_zero_flag
642  ap.armed_with_switch = true;
643  break;
644  case AUX_SWITCH_LOW:
645  init_disarm_motors();
646  break;
647  }
648  break;
649 
650  case AUXSW_SMART_RTL:
651 #if MODE_SMARTRTL_ENABLED == ENABLED
652  if (ch_flag == AUX_SWITCH_HIGH) {
653  // engage SmartRTL (if not possible we remain in current flight mode)
655  } else {
656  // return to flight mode switch's flight mode if we are currently in RTL
657  if (control_mode == SMART_RTL) {
658  reset_control_switch();
659  }
660  }
661 #endif
662  break;
663 
664  case AUXSW_INVERTED:
665 #if FRAME_CONFIG == HELI_FRAME
666  // inverted flight option is disabled for heli single and dual frames
667  if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_QUAD) {
668  switch (ch_flag) {
669  case AUX_SWITCH_HIGH:
670  motors->set_inverted_flight(true);
671  attitude_control->set_inverted_flight(true);
672  heli_flags.inverted_flight = true;
673  break;
674  case AUX_SWITCH_LOW:
675  motors->set_inverted_flight(false);
676  attitude_control->set_inverted_flight(false);
677  heli_flags.inverted_flight = false;
678  break;
679  }
680  }
681 #endif
682  break;
683 
684  case AUXSW_WINCH_ENABLE:
685 #if WINCH_ENABLED == ENABLED
686  switch (ch_flag) {
687  case AUX_SWITCH_HIGH:
688  // high switch maintains current position
689  g2.winch.release_length(0.0f);
690  Log_Write_Event(DATA_WINCH_LENGTH_CONTROL);
691  break;
692  default:
693  // all other position relax winch
694  g2.winch.relax();
695  Log_Write_Event(DATA_WINCH_RELAXED);
696  break;
697  }
698 #endif
699  break;
700 
701  case AUXSW_WINCH_CONTROL:
702 #if WINCH_ENABLED == ENABLED
703  switch (ch_flag) {
704  case AUX_SWITCH_LOW:
705  // raise winch at maximum speed
706  g2.winch.set_desired_rate(-g2.winch.get_rate_max());
707  break;
708  case AUX_SWITCH_HIGH:
709  // lower winch at maximum speed
710  g2.winch.set_desired_rate(g2.winch.get_rate_max());
711  break;
712  case AUX_SWITCH_MIDDLE:
713  default:
714  g2.winch.set_desired_rate(0.0f);
715  break;
716  }
717 #endif
718  break;
719 
721  // Allow or disallow RC_Override
722  switch (ch_flag) {
723  case AUX_SWITCH_HIGH: {
724  ap.rc_override_enable = true;
725  break;
726  }
727  case AUX_SWITCH_LOW: {
728  ap.rc_override_enable = false;
729  break;
730  }
731  }
732  break;
733  }
734 }
735 
736 // save_trim - adds roll and pitch trims from the radio to ahrs
738 {
739  // save roll and pitch trim
740  float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
741  float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
742  ahrs.add_trim(roll_trim, pitch_trim);
743  Log_Write_Event(DATA_SAVE_TRIM);
744  gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
745 }
746 
747 // auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions
748 // meant to be called continuously while the pilot attempts to keep the copter level
750 {
751  if (auto_trim_counter > 0) {
752  auto_trim_counter--;
753 
754  // flash the leds
756 
757  // calculate roll trim adjustment
758  float roll_trim_adjustment = ToRad((float)channel_roll->get_control_in() / 4000.0f);
759 
760  // calculate pitch trim adjustment
761  float pitch_trim_adjustment = ToRad((float)channel_pitch->get_control_in() / 4000.0f);
762 
763  // add trim to ahrs object
764  // save to eeprom on last iteration
765  ahrs.add_trim(roll_trim_adjustment, pitch_trim_adjustment, (auto_trim_counter == 0));
766 
767  // on last iteration restore leds and accel gains to normal
768  if (auto_trim_counter == 0) {
769  AP_Notify::flags.save_trim = false;
770  }
771  }
772 }
773 
void read_aux_switches()
Definition: switches.cpp:135
void init_aux_switch_function(int8_t ch_option, uint8_t ch_flag)
Definition: switches.cpp:182
#define AUX_SWITCH_PWM_TRIGGER_LOW
Definition: defines.h:26
uint8_t CH6_flag
Definition: switches.cpp:7
uint8_t CH9_flag
Definition: switches.cpp:10
control_mode_t
Definition: defines.h:91
void read_control_switch()
Definition: switches.cpp:16
AP_AHRS_NavEKF & ahrs
ROTATION_PITCH_270
#define AUX_SWITCH_HIGH
Definition: defines.h:31
#define AUX_SWITCH_LOW
Definition: defines.h:29
#define DATA_ACRO_TRAINER_LEVELING
Definition: defines.h:365
#define DATA_FENCE_ENABLE
Definition: defines.h:362
int16_t get_radio_in() const
static RC_Channel * rc_channel(uint8_t chan)
#define ToRad(x)
#define DATA_ACRO_TRAINER_LIMITED
Definition: defines.h:366
#define DATA_GRIPPER_RELEASE
Definition: defines.h:368
Definition: defines.h:95
Definition: defines.h:106
#define CH_9
#define read_aux_switch(chan, flag, option)
Definition: switches.cpp:125
void save_trim()
Definition: switches.cpp:737
#define DATA_AVOIDANCE_PROXIMITY_ENABLE
Definition: defines.h:385
Definition: defines.h:100
#define CONTROL_SWITCH_DEBOUNCE_TIME_MS
Definition: switches.cpp:3
GCS & gcs()
#define CH_11
#define ACRO_TRAINER_DISABLED
Definition: defines.h:183
uint8_t CH11_flag
Definition: switches.cpp:12
uint8_t ch_flag
Definition: Copter.h:361
#define ACRO_TRAINER_LEVELING
Definition: defines.h:184
virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom=true)
uint8_t read_3pos_switch(uint8_t chan)
Definition: switches.cpp:116
int32_t lat
#define DATA_PARACHUTE_ENABLED
Definition: defines.h:370
AP_MotorsMatrix motors(400)
void auto_trim()
Definition: switches.cpp:749
void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
Definition: switches.cpp:239
bool armed() const
void reset_control_switch()
Definition: switches.cpp:109
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check)
Definition: switches.cpp:79
bool check_duplicate_auxsw(void)
Definition: switches.cpp:88
Definition: defines.h:93
#define DATA_WINCH_LENGTH_CONTROL
Definition: defines.h:389
#define AUX_SWITCH_PWM_TRIGGER_HIGH
Definition: defines.h:25
#define DATA_AVOIDANCE_ADSB_DISABLE
Definition: defines.h:384
int32_t alt
#define DATA_PARACHUTE_DISABLED
Definition: defines.h:369
#define f(i)
#define DATA_WINCH_RELAXED
Definition: defines.h:388
Definition: defines.h:103
uint32_t millis()
void init_aux_switches()
Definition: switches.cpp:158
bool debounce_aux_switch(uint8_t chan, uint8_t ch_flag)
Definition: switches.cpp:216
uint8_t CH12_flag
Definition: switches.cpp:13
#define BIT_IS_SET(value, bitnumber)
#define DATA_AVOIDANCE_ADSB_ENABLE
Definition: defines.h:383
#define DATA_FENCE_DISABLE
Definition: defines.h:363
Definition: defines.h:107
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define DATA_GRIPPER_GRAB
Definition: defines.h:367
int32_t lng
uint8_t count
Definition: Copter.h:360
#define CH_12
uint8_t CH8_flag
Definition: switches.cpp:9
#define DATA_AVOIDANCE_PROXIMITY_DISABLE
Definition: defines.h:386
static struct notify_flags_and_values_type flags
#define DATA_ACRO_TRAINER_DISABLED
Definition: defines.h:364
#define ACRO_TRAINER_LIMITED
Definition: defines.h:185
#define CH_10
uint8_t CH10_flag
Definition: switches.cpp:11
#define AUX_SWITCH_MIDDLE
Definition: defines.h:30
#define CH_8
#define DATA_SAVE_TRIM
Definition: defines.h:360
#define CH_7
static struct notify_events_type events
uint8_t CH7_flag
Definition: switches.cpp:8
struct @17 aux_con
#define DATA_SAVEWP_ADD_WP
Definition: defines.h:361
uint8_t options
Definition: defines.h:98