From 8e40cbdd7faf351848949fdba57e3d03a70a86cb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 23 Jan 2014 14:13:51 +0900 Subject: [PATCH] Copter: disable ch7/8 feature to point at armed yaw --- ArduCopter/control_modes.pde | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 6cd5d382b3..60f702089d 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -276,13 +276,14 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) } break; #endif - case AUX_SWITCH_RESETTOARMEDYAW: - if (ch_flag == AUX_SWITCH_HIGH) { - set_yaw_mode(YAW_RESETTOARMEDYAW); - }else{ - set_yaw_mode(YAW_HOLD); - } - break; + // To-Do: add back support for this feature + //case AUX_SWITCH_RESETTOARMEDYAW: + // if (ch_flag == AUX_SWITCH_HIGH) { + // set_yaw_mode(YAW_RESETTOARMEDYAW); + // }else{ + // set_yaw_mode(YAW_HOLD); + // } + // break; case AUX_SWITCH_ACRO_TRAINER: switch(ch_flag) {