Browse Source

Copter: default Ch7 to DO_NOTHING

Ch7/Ch8 Save_WP feature triggers when switch is brought high (instead of
low) to be consistent with other aux features
master
Randy Mackay 11 years ago
parent
commit
babc54ec60
  1. 2
      ArduCopter/config.h
  2. 4
      ArduCopter/control_modes.pde

2
ArduCopter/config.h

@ -286,7 +286,7 @@ @@ -286,7 +286,7 @@
//
#ifndef CH7_OPTION
# define CH7_OPTION AUX_SWITCH_SAVE_WP
# define CH7_OPTION AUX_SWITCH_DO_NOTHING
#endif
#ifndef CH8_OPTION

4
ArduCopter/control_modes.pde

@ -178,8 +178,8 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) @@ -178,8 +178,8 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break;
case AUX_SWITCH_SAVE_WP:
// save waypoint when switch is switched off
if (ch_flag == AUX_SWITCH_LOW) {
// save waypoint when switch is brought high
if (ch_flag == AUX_SWITCH_HIGH) {
// if in auto mode, reset the mission
if(control_mode == AUTO) {

Loading…
Cancel
Save