From b931bfaf501abbff4351ff6e76c7c8db66526767 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Fri, 5 Aug 2011 16:21:55 +0000 Subject: [PATCH] 2.0.39 added defines for CH7 behavior git-svn-id: https://arducopter.googlecode.com/svn/trunk@3022 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/control_modes.pde | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ArduCopterMega/control_modes.pde b/ArduCopterMega/control_modes.pde index f6602ec3c7..329ae5519a 100644 --- a/ArduCopterMega/control_modes.pde +++ b/ArduCopterMega/control_modes.pde @@ -49,6 +49,12 @@ static unsigned long trim_timer; // set this to your trainer switch static void read_trim_switch() { +#if CH7_OPTION == DO_FLIP + if (g.rc_7.control_in > 800 && g.rc_3.control_in != 0){ + do_flip = true; + } + +#elif CH7_OPTION == DO_SET_HOVER // switch is engaged if (g.rc_7.control_in > 800){ trim_flag = true; @@ -63,8 +69,10 @@ static void read_trim_switch() //Serial.printf("tnom %d\n", g.throttle_cruise.get()); } trim_flag = false; + } } +#endif } static void auto_trim()