|
|
@ -395,42 +395,42 @@ const AP_Param::Info Copter::var_info[] = {
|
|
|
|
// @Param: CH7_OPT
|
|
|
|
// @Param: CH7_OPT
|
|
|
|
// @DisplayName: Channel 7 option
|
|
|
|
// @DisplayName: Channel 7 option
|
|
|
|
// @Description: Select which function is performed when CH7 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH7 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
|
// @Param: CH8_OPT
|
|
|
|
// @Param: CH8_OPT
|
|
|
|
// @DisplayName: Channel 8 option
|
|
|
|
// @DisplayName: Channel 8 option
|
|
|
|
// @Description: Select which function is performed when CH8 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH8 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
|
// @Param: CH9_OPT
|
|
|
|
// @Param: CH9_OPT
|
|
|
|
// @DisplayName: Channel 9 option
|
|
|
|
// @DisplayName: Channel 9 option
|
|
|
|
// @Description: Select which function is performed when CH9 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH9 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
|
// @Param: CH10_OPT
|
|
|
|
// @Param: CH10_OPT
|
|
|
|
// @DisplayName: Channel 10 option
|
|
|
|
// @DisplayName: Channel 10 option
|
|
|
|
// @Description: Select which function is performed when CH10 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH10 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
|
// @Param: CH11_OPT
|
|
|
|
// @Param: CH11_OPT
|
|
|
|
// @DisplayName: Channel 11 option
|
|
|
|
// @DisplayName: Channel 11 option
|
|
|
|
// @Description: Select which function is performed when CH11 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH11 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
|
// @Param: CH12_OPT
|
|
|
|
// @Param: CH12_OPT
|
|
|
|
// @DisplayName: Channel 12 option
|
|
|
|
// @DisplayName: Channel 12 option
|
|
|
|
// @Description: Select which function is performed when CH12 is above 1800 pwm
|
|
|
|
// @Description: Select which function is performed when CH12 is above 1800 pwm
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 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, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 37:Throw, 38:Avoidance
|
|
|
|
// @User: Standard
|
|
|
|
// @User: Standard
|
|
|
|
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
|
|
|
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
|
|
|
|
|
|
|
|
|
|
|
@ -1039,6 +1039,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|
|
|
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
|
|
|
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
|
|
|
AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
|
|
|
|
AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats),
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if GRIPPER_ENABLED == ENABLED
|
|
|
|
|
|
|
|
// @Group: GRIP_
|
|
|
|
|
|
|
|
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
|
|
|
|
|
|
|
|
AP_SUBGROUPINFO(gripper, "GRIP_", 13, ParametersG2, AP_Gripper),
|
|
|
|
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_GROUPEND
|
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|