Copter: remove CH7_OPTION definition
We can replace the unused definitions and just set the aux switch defaults to do-nothing directly in the parameter table
This commit is contained in:
parent
e6c3f4f97b
commit
20311c3ba2
@ -348,42 +348,42 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @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, 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),
|
||||
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @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, 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),
|
||||
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH9_OPT
|
||||
// @DisplayName: Channel 9 option
|
||||
// @Description: Select which function if performed when CH9 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, 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(ch9_option, "CH9_OPT", CH9_OPTION),
|
||||
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH10_OPT
|
||||
// @DisplayName: Channel 10 option
|
||||
// @Description: Select which function if performed when CH10 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, 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(ch10_option, "CH10_OPT", CH10_OPTION),
|
||||
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH11_OPT
|
||||
// @DisplayName: Channel 11 option
|
||||
// @Description: Select which function if performed when CH11 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, 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(ch11_option, "CH11_OPT", CH11_OPTION),
|
||||
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: CH12_OPT
|
||||
// @DisplayName: Channel 12 option
|
||||
// @Description: Select which function if performed when CH12 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, 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(ch12_option, "CH12_OPT", CH12_OPTION),
|
||||
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
||||
|
||||
// @Param: ARMING_CHECK
|
||||
// @DisplayName: Arming check
|
||||
|
@ -179,34 +179,6 @@
|
||||
# define SONAR_TILT_CORRECTION DISABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Channel 7 and 8 default options
|
||||
//
|
||||
|
||||
#ifndef CH7_OPTION
|
||||
# define CH7_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
#ifndef CH8_OPTION
|
||||
# define CH8_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
#ifndef CH9_OPTION
|
||||
# define CH9_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
#ifndef CH10_OPTION
|
||||
# define CH10_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
#ifndef CH11_OPTION
|
||||
# define CH11_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
#ifndef CH12_OPTION
|
||||
# define CH12_OPTION AUXSW_DO_NOTHING
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_MODE OPTIONAL
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user