From 9dad38e91de4d1f8f2b6df75ed3bfc6eb062497a Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 18 Jul 2012 22:36:05 -0700 Subject: [PATCH] Arducopter: Flip mode Flip mode graduates --- ArduCopter/control_modes.pde | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 8b5467d04a..5669bc45d5 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -47,11 +47,7 @@ static void reset_control_switch() // set this to your trainer switch static void read_trim_switch() { - #if CH7_OPTION == CH7_FLIP - if (g.rc_7.radio_in > CH_7_PWM_TRIGGER && g.rc_3.control_in != 0){ - init_flip(); - } - #elif CH7_OPTION == CH7_SET_HOVER + #if CH7_OPTION == CH7_SET_HOVER // switch is engaged if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){ trim_flag = true; @@ -76,6 +72,11 @@ static void read_trim_switch() if(g.ch7_option == CH7_SIMPLE_MODE){ do_simple = (g.rc_7.radio_in > CH_7_PWM_TRIGGER); + }else if (g.ch7_option == CH7_FLIP){ + if (g.rc_7.radio_in > CH_7_PWM_TRIGGER && g.rc_3.control_in != 0){ + init_flip(); + } + }else if (g.ch7_option == CH7_RTL){ if (trim_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER){ trim_flag = true;