Copter: remove USE_EKF from ch7/ch8 switch
This commit is contained in:
parent
1f70b34cbc
commit
0476558049
@ -362,14 +362,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:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear
|
||||
// @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:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
|
@ -48,7 +48,7 @@
|
||||
#define AUX_SWITCH_AUTOTUNE 17 // auto tune
|
||||
#define AUX_SWITCH_LAND 18 // change to LAND flight mode
|
||||
#define AUX_SWITCH_EPM 19 // Operate the EPM cargo gripper low=off, middle=neutral, high=on
|
||||
#define AUX_SWITCH_EKF 20 // Enable NavEKF
|
||||
#define AUX_SWITCH_EKF 20 // deprecated
|
||||
#define AUX_SWITCH_PARACHUTE_ENABLE 21 // Parachute enable/disable
|
||||
#define AUX_SWITCH_PARACHUTE_RELEASE 22 // Parachute release
|
||||
#define AUX_SWITCH_PARACHUTE_3POS 23 // Parachute disable, enable, release with 3 position switch
|
||||
|
@ -119,7 +119,6 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_ACRO_TRAINER:
|
||||
case AUX_SWITCH_EPM:
|
||||
case AUX_SWITCH_SPRAYER:
|
||||
case AUX_SWITCH_EKF:
|
||||
case AUX_SWITCH_PARACHUTE_ENABLE:
|
||||
case AUX_SWITCH_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
case AUX_SWITCH_RETRACT_MOUNT:
|
||||
@ -142,7 +141,6 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_ACRO_TRAINER:
|
||||
case AUX_SWITCH_EPM:
|
||||
case AUX_SWITCH_SPRAYER:
|
||||
case AUX_SWITCH_EKF:
|
||||
case AUX_SWITCH_PARACHUTE_ENABLE:
|
||||
case AUX_SWITCH_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
case AUX_SWITCH_RETRACT_MOUNT:
|
||||
@ -381,12 +379,6 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
}
|
||||
break;
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
case AUX_SWITCH_EKF:
|
||||
ahrs.set_ekf_use(ch_flag==AUX_SWITCH_HIGH);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if PARACHUTE == ENABLED
|
||||
case AUX_SWITCH_PARACHUTE_ENABLE:
|
||||
// Parachute enable/disable
|
||||
|
Loading…
Reference in New Issue
Block a user