From 249c757b9406151263dc03ec4fc428c596d5ff1b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Nov 2013 11:42:33 +0900 Subject: [PATCH] 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 --- ArduCopter/config.h | 2 +- ArduCopter/control_modes.pde | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 5bf352d34d..5a5275c688 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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 diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 7270c52bdd..8fda2f4d43 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -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) {