mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-17 13:23:56 -04:00
Copter: AUTO ch7/ch8 option
This commit is contained in:
parent
2696e160e6
commit
fd047cc968
ArduCopter
@ -412,14 +412,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, 14:Acro Trainer
|
||||
// @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, 16:Auto
|
||||
// @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, 14:Acro Trainer
|
||||
// @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, 16:Auto
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
|
@ -262,6 +262,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
g.acro_trainer = ACRO_TRAINER_LIMITED;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
#if SPRAYER == ENABLED
|
||||
case AUX_SWITCH_SPRAYER:
|
||||
@ -269,16 +270,11 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AUX_SWITCH_AUTO_AND_LAND:
|
||||
switch(ch_flag) {
|
||||
case AUX_SWITCH_LOW:
|
||||
case AUX_SWITCH_MIDDLE:
|
||||
set_mode(LAND);
|
||||
break;
|
||||
case AUX_SWITCH_HIGH:
|
||||
set_mode(AUTO);
|
||||
break;
|
||||
case AUX_SWITCH_AUTO:
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
set_mode(AUTO);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -67,7 +67,7 @@
|
||||
#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
|
||||
#define AUX_SWITCH_SPRAYER 15 // enable/disable the crop sprayer
|
||||
#define AUX_SWITCH_AUTO_AND_LAND 16 // switch enabled auto (high) or land (low) flight modes
|
||||
#define AUX_SWITCH_AUTO 16 // change to auto flight mode
|
||||
|
||||
// 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)
|
||||
|
Loading…
Reference in New Issue
Block a user