Edited CH7 options to include Do Nothing and RTL.

This commit is contained in:
Jason Short 2011-09-20 10:37:50 -07:00
parent b2b28cc90c
commit 020062498b
4 changed files with 19 additions and 12 deletions

View File

@ -48,11 +48,13 @@
CH6_TRAVERSE_SPEED
*/
# define CH7_OPTION DO_SET_HOVER
# define CH7_OPTION CH7_DO_NOTHING
/*
DO_SET_HOVER
DO_FLIP
SIMPLE_MODE_CONTROL
CH7_DO_NOTHING
CH7_SET_HOVER
CH7_FLIP
CH7_SIMPLE_MODE
CH7_RTL
*/
// See the config.h and defines.h files for how to set this up!

View File

@ -525,7 +525,6 @@ void loop()
//PORTK |= B00010000;
G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops
fast_loopTimer = timer;
//Serial.printf("%1.5f\n", G_Dt);
// Execute the fast loop
// ---------------------

View File

@ -51,17 +51,22 @@ static boolean trim_flag;
// set this to your trainer switch
static void read_trim_switch()
{
#if CH7_OPTION == DO_FLIP
#if CH7_OPTION == CH7_FLIP
if (g.rc_7.control_in > 800 && g.rc_3.control_in != 0){
do_flip = true;
}
#elif CH7_OPTION == SIMPLE_MODE_CONTROL
#elif CH7_OPTION == CH7_SIMPLE_MODE
do_simple = (g.rc_7.control_in > 800);
//Serial.println(g.rc_7.control_in, DEC);
#elif CH7_OPTION == DO_SET_HOVER
#elif CH7_OPTION == CH7_RTL
set_mode(RTL);
//do_simple = (g.rc_7.control_in > 800);
//Serial.println(g.rc_7.control_in, DEC);
#elif CH7_OPTION == CH7_SET_HOVER
// switch is engaged
if (g.rc_7.control_in > 800){
trim_flag = true;
@ -76,7 +81,6 @@ static void read_trim_switch()
//Serial.printf("tnom %d\n", g.throttle_cruise.get());
}
trim_flag = false;
}
}
#endif

View File

@ -27,9 +27,11 @@
#define BARO 1
// CH 7 control
#define DO_SET_HOVER 0
#define DO_FLIP 1
#define SIMPLE_MODE_CONTROL 2
#define CH7_DO_NOTHING 0
#define CH7_SET_HOVER 1
#define CH7_FLIP 2
#define CH7_SIMPLE_MODE 3
#define CH7_RTL 4
// Frame types
#define QUAD_FRAME 0