ACM: Restore Multi-mode support
This commit is contained in:
parent
bd0e018ca0
commit
8b62c4630b
@ -60,7 +60,22 @@ static void read_trim_switch()
|
|||||||
// set the ch7 flag
|
// set the ch7 flag
|
||||||
ap_system.CH7_flag = (g.rc_7.radio_in >= CH7_PWM_TRIGGER);
|
ap_system.CH7_flag = (g.rc_7.radio_in >= CH7_PWM_TRIGGER);
|
||||||
|
|
||||||
switch(g.ch7_option) {
|
// multi-mode
|
||||||
|
int8_t option;
|
||||||
|
|
||||||
|
if(g.ch7_option == CH7_MULTI_MODE) {
|
||||||
|
if (g.rc_6.radio_in < CH6_PWM_TRIGGER_LOW) {
|
||||||
|
option = CH7_FLIP;
|
||||||
|
}else if (g.rc_6.radio_in > CH6_PWM_TRIGGER_HIGH) {
|
||||||
|
option = CH7_SAVE_WP;
|
||||||
|
}else{
|
||||||
|
option = CH7_RTL;
|
||||||
|
}
|
||||||
|
}else{
|
||||||
|
option = g.ch7_option;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch(option) {
|
||||||
case CH7_FLIP:
|
case CH7_FLIP:
|
||||||
// flip if switch is on, positive throttle and we're actually flying
|
// flip if switch is on, positive throttle and we're actually flying
|
||||||
if(ap_system.CH7_flag && g.rc_3.control_in >= 0 && ap.takeoff_complete) {
|
if(ap_system.CH7_flag && g.rc_3.control_in >= 0 && ap.takeoff_complete) {
|
||||||
|
@ -53,6 +53,9 @@
|
|||||||
|
|
||||||
// CH 7 control
|
// CH 7 control
|
||||||
#define CH7_PWM_TRIGGER 1800 // pwm value above which the channel 7 option will be invoked
|
#define CH7_PWM_TRIGGER 1800 // pwm value above which the channel 7 option will be invoked
|
||||||
|
#define CH6_PWM_TRIGGER_HIGH 1800
|
||||||
|
#define CH6_PWM_TRIGGER_LOW 1200
|
||||||
|
|
||||||
#define CH7_DO_NOTHING 0
|
#define CH7_DO_NOTHING 0
|
||||||
#define CH7_SET_HOVER 1 // deprecated
|
#define CH7_SET_HOVER 1 // deprecated
|
||||||
#define CH7_FLIP 2
|
#define CH7_FLIP 2
|
||||||
@ -61,10 +64,11 @@
|
|||||||
#define CH7_SAVE_TRIM 5
|
#define CH7_SAVE_TRIM 5
|
||||||
#define CH7_ADC_FILTER 6 // deprecated
|
#define CH7_ADC_FILTER 6 // deprecated
|
||||||
#define CH7_SAVE_WP 7
|
#define CH7_SAVE_WP 7
|
||||||
#define CH7_MULTI_MODE 8 // deprecated
|
#define CH7_MULTI_MODE 8
|
||||||
#define CH7_CAMERA_TRIGGER 9
|
#define CH7_CAMERA_TRIGGER 9
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Frame types
|
// Frame types
|
||||||
#define QUAD_FRAME 0
|
#define QUAD_FRAME 0
|
||||||
#define TRI_FRAME 1
|
#define TRI_FRAME 1
|
||||||
|
Loading…
Reference in New Issue
Block a user