Added Auto_trim to CH7 option
This commit is contained in:
parent
39cefe9554
commit
c2d56de264
@ -48,13 +48,14 @@
|
|||||||
CH6_TRAVERSE_SPEED
|
CH6_TRAVERSE_SPEED
|
||||||
*/
|
*/
|
||||||
|
|
||||||
# define CH7_OPTION CH7_DO_NOTHING
|
# define CH7_OPTION CH7_RTL
|
||||||
/*
|
/*
|
||||||
CH7_DO_NOTHING
|
CH7_DO_NOTHING
|
||||||
CH7_SET_HOVER
|
CH7_SET_HOVER
|
||||||
CH7_FLIP
|
CH7_FLIP
|
||||||
CH7_SIMPLE_MODE
|
CH7_SIMPLE_MODE
|
||||||
CH7_RTL
|
CH7_RTL
|
||||||
|
CH7_AUTO_TRIM
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// See the config.h and defines.h files for how to set this up!
|
// See the config.h and defines.h files for how to set this up!
|
||||||
|
@ -62,8 +62,12 @@ static void read_trim_switch()
|
|||||||
//Serial.println(g.rc_7.control_in, DEC);
|
//Serial.println(g.rc_7.control_in, DEC);
|
||||||
|
|
||||||
#elif CH7_OPTION == CH7_RTL
|
#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)
|
if(control_mode != RTL && g.rc_7.control_in > 800)
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
|
|
||||||
//do_simple = (g.rc_7.control_in > 800);
|
//do_simple = (g.rc_7.control_in > 800);
|
||||||
//Serial.println(g.rc_7.control_in, DEC);
|
//Serial.println(g.rc_7.control_in, DEC);
|
||||||
|
|
||||||
@ -84,7 +88,12 @@ static void read_trim_switch()
|
|||||||
trim_flag = false;
|
trim_flag = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#elif CH7_OPTION == CH7_AUTO_TRIM
|
||||||
|
if (g.rc_7.control_in > 800){
|
||||||
|
auto_level_counter = 10;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void auto_trim()
|
static void auto_trim()
|
||||||
|
@ -32,6 +32,7 @@
|
|||||||
#define CH7_FLIP 2
|
#define CH7_FLIP 2
|
||||||
#define CH7_SIMPLE_MODE 3
|
#define CH7_SIMPLE_MODE 3
|
||||||
#define CH7_RTL 4
|
#define CH7_RTL 4
|
||||||
|
#deinfe CH7_AUTO_TRIM 5
|
||||||
|
|
||||||
// Frame types
|
// Frame types
|
||||||
#define QUAD_FRAME 0
|
#define QUAD_FRAME 0
|
||||||
|
Loading…
Reference in New Issue
Block a user