added defines for CH7 behavior

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3022 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-08-05 16:21:55 +00:00
parent 6748ffd112
commit 834de9f6c7

View File

@ -49,6 +49,12 @@ static unsigned long trim_timer;
// set this to your trainer switch // set this to your trainer switch
static void read_trim_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 // switch is engaged
if (g.rc_7.control_in > 800){ if (g.rc_7.control_in > 800){
trim_flag = true; trim_flag = true;
@ -63,8 +69,10 @@ static void read_trim_switch()
//Serial.printf("tnom %d\n", g.throttle_cruise.get()); //Serial.printf("tnom %d\n", g.throttle_cruise.get());
} }
trim_flag = false; trim_flag = false;
} }
} }
#endif
} }
static void auto_trim() static void auto_trim()