Copter: Acro Trainer added to Ch7/Ch8 switch

This commit is contained in:
Randy Mackay 2013-08-04 18:33:23 +09:00
parent 21e523b9ac
commit 786d6824ae
3 changed files with 19 additions and 3 deletions

View File

@ -405,14 +405,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: CH7_OPT
// @DisplayName: Channel 7 option
// @Description: Select which function if performed when CH7 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer
// @User: Standard
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
// @Param: CH8_OPT
// @DisplayName: Channel 8 option
// @Description: Select which function if performed when CH8 is above 1800 pwm
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer
// @User: Standard
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),

View File

@ -97,6 +97,7 @@ static void init_aux_switches()
case AUX_SWITCH_FENCE:
case AUX_SWITCH_RESETTOARMEDYAW:
case AUX_SWITCH_SUPERSIMPLE_MODE:
case AUX_SWITCH_ACRO_TRAINER:
do_aux_switch_function(g.ch7_option, ap_system.CH7_flag);
break;
}
@ -107,6 +108,7 @@ static void init_aux_switches()
case AUX_SWITCH_FENCE:
case AUX_SWITCH_RESETTOARMEDYAW:
case AUX_SWITCH_SUPERSIMPLE_MODE:
case AUX_SWITCH_ACRO_TRAINER:
do_aux_switch_function(g.ch8_option, ap_system.CH8_flag);
break;
}
@ -245,6 +247,19 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
set_yaw_mode(YAW_HOLD);
}
break;
case AUX_SWITCH_ACRO_TRAINER:
switch(ch_flag) {
case AUX_SWITCH_LOW:
g.acro_trainer = ACRO_TRAINER_DISABLED;
break;
case AUX_SWITCH_MIDDLE:
g.acro_trainer = ACRO_TRAINER_LEVELING;
break;
case AUX_SWITCH_HIGH:
g.acro_trainer = ACRO_TRAINER_LIMITED;
break;
}
}
}

View File

@ -65,6 +65,7 @@
#define AUX_SWITCH_FENCE 11 // allow enabling or disabling fence in flight
#define AUX_SWITCH_RESETTOARMEDYAW 12 // changes yaw to be same as when quad was armed
#define AUX_SWITCH_SUPERSIMPLE_MODE 13 // change to simple mode in middle, super simple at top
#define AUX_SWITCH_ACRO_TRAINER 14 // low = disabled, middle = leveled, high = leveled and limited
// values used by the ap.ch7_opt and ap.ch8_opt flags
#define AUX_SWITCH_LOW 0 // indicates auxiliar switch is in the low position (pwm <1200)