From c2d56de26418df42babec5bf35717c8c1bfed087 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 21 Sep 2011 16:24:09 -0700 Subject: [PATCH] Added Auto_trim to CH7 option --- ArduCopter/APM_Config.h | 3 ++- ArduCopter/control_modes.pde | 9 +++++++++ ArduCopter/defines.h | 1 + 3 files changed, 12 insertions(+), 1 deletion(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 89d30859a3..8cdc69d950 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -48,13 +48,14 @@ CH6_TRAVERSE_SPEED */ -# define CH7_OPTION CH7_DO_NOTHING +# define CH7_OPTION CH7_RTL /* CH7_DO_NOTHING CH7_SET_HOVER CH7_FLIP CH7_SIMPLE_MODE CH7_RTL + CH7_AUTO_TRIM */ // See the config.h and defines.h files for how to set this up! diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 7e7b5c6456..90254fa29b 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -62,8 +62,12 @@ static void read_trim_switch() //Serial.println(g.rc_7.control_in, DEC); #elif CH7_OPTION == CH7_RTL + if(control_mode == RTL && g.rc_7.control_in < 800){ + reset_control_switch(); + } if(control_mode != RTL && g.rc_7.control_in > 800) set_mode(RTL); + //do_simple = (g.rc_7.control_in > 800); //Serial.println(g.rc_7.control_in, DEC); @@ -84,7 +88,12 @@ static void read_trim_switch() trim_flag = false; } } +#elif CH7_OPTION == CH7_AUTO_TRIM + if (g.rc_7.control_in > 800){ + auto_level_counter = 10; + } #endif + } static void auto_trim() diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 58070376dc..70d6dc3d04 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -32,6 +32,7 @@ #define CH7_FLIP 2 #define CH7_SIMPLE_MODE 3 #define CH7_RTL 4 +#deinfe CH7_AUTO_TRIM 5 // Frame types #define QUAD_FRAME 0