|
|
|
@ -366,48 +366,6 @@ const AP_Param::Info Copter::var_info[] = {
@@ -366,48 +366,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|
|
|
|
// @RebootRequired: True
|
|
|
|
|
GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X), |
|
|
|
|
|
|
|
|
|
// @Param: CH7_OPT
|
|
|
|
|
// @DisplayName: Channel 7 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch7_option, "CH7_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Param: CH8_OPT
|
|
|
|
|
// @DisplayName: Channel 8 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch8_option, "CH8_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Param: CH9_OPT
|
|
|
|
|
// @DisplayName: Channel 9 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch9_option, "CH9_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Param: CH10_OPT
|
|
|
|
|
// @DisplayName: Channel 10 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch10_option, "CH10_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Param: CH11_OPT
|
|
|
|
|
// @DisplayName: Channel 11 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch11_option, "CH11_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Param: CH12_OPT
|
|
|
|
|
// @DisplayName: Channel 12 option
|
|
|
|
|
// @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: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:ADSB-Avoidance, 39:PrecLoiter, 40:Object Avoidance, 41:ArmDisarm, 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 45:WinchControl
|
|
|
|
|
// @User: Standard
|
|
|
|
|
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING), |
|
|
|
|
|
|
|
|
|
// @Group: ARMING_
|
|
|
|
|
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
|
|
|
|
|
GOBJECT(arming, "ARMING_", AP_Arming_Copter), |
|
|
|
@ -922,7 +880,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
@@ -922,7 +880,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|
|
|
|
|
|
|
|
|
// @Group: RC
|
|
|
|
|
// @Path: ../libraries/RC_Channel/RC_Channels.cpp
|
|
|
|
|
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels), |
|
|
|
|
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels_Copter), |
|
|
|
|
|
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED |
|
|
|
|
// @Group: VISO
|
|
|
|
@ -1046,6 +1004,13 @@ const AP_Param::ConversionInfo conversion_table[] = {
@@ -1046,6 +1004,13 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
|
|
|
|
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_INT8, "BATT_FS_LOW_VOLT" }, |
|
|
|
|
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_INT8, "BATT_FS_LOW_MAH" }, |
|
|
|
|
{ Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" }, |
|
|
|
|
|
|
|
|
|
{ Parameters::Parameters::k_param_ch7_option_old, 0, AP_PARAM_INT8, "RC7_OPTION" }, |
|
|
|
|
{ Parameters::Parameters::k_param_ch8_option_old, 0, AP_PARAM_INT8, "RC8_OPTION" }, |
|
|
|
|
{ Parameters::Parameters::k_param_ch9_option_old, 0, AP_PARAM_INT8, "RC9_OPTION" }, |
|
|
|
|
{ Parameters::Parameters::k_param_ch10_option_old, 0, AP_PARAM_INT8, "RC10_OPTION" }, |
|
|
|
|
{ Parameters::Parameters::k_param_ch11_option_old, 0, AP_PARAM_INT8, "RC11_OPTION" }, |
|
|
|
|
{ Parameters::Parameters::k_param_ch12_option_old, 0, AP_PARAM_INT8, "RC12_OPTION" }, |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
void Copter::load_parameters(void) |
|
|
|
|