Sub: Remove deprecated parameters

This commit is contained in:
Jacob Walser 2016-11-25 14:09:03 -05:00 committed by Andrew Tridgell
parent a430f5a7ae
commit d75919eadc
3 changed files with 6 additions and 207 deletions

View File

@ -437,42 +437,42 @@ const AP_Param::Info Sub::var_info[] = {
// @Param: CH7_OPT // @Param: CH7_OPT
// @DisplayName: Channel 7 option // @DisplayName: Channel 7 option
// @Description: Select which function if performed when CH7 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @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 if performed when CH8 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @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 if performed when CH9 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @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 if performed when CH10 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @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 if performed when CH11 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @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 if performed when CH12 is above 1800 pwm // @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, 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, 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 // @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 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
// @User: Standard // @User: Standard
GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING), GSCALAR(ch12_option, "CH12_OPT", AUXSW_DO_NOTHING),
@ -1122,32 +1122,6 @@ ParametersG2::ParametersG2(void)
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }
/*
This is a conversion table from old parameter values to new
parameter names. The startup code looks for saved values of the old
parameters and will copy them across to the new parameters if the
new parameter does not yet have a saved value. It then saves the new
value.
Note that this works even if the old parameter has been removed. It
relies on the old k_param index not being removed
The second column below is the index in the var_info[] table for the
old object. This should be zero for top level parameters.
*/
const AP_Param::ConversionInfo conversion_table[] = {
{ Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" },
{ Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" },
{ Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" },
{ Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },
{ Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },
{ Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },
{ Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" },
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
};
void Sub::load_parameters(void) void Sub::load_parameters(void)
{ {
if (!AP_Param::check_var_info()) { if (!AP_Param::check_var_info()) {
@ -1174,73 +1148,5 @@ void Sub::load_parameters(void)
uint32_t before = micros(); uint32_t before = micros();
// Load all auto-loaded EEPROM variables // Load all auto-loaded EEPROM variables
AP_Param::load_all(); AP_Param::load_all();
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before)); cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
// upgrade parameters
convert_pid_parameters();
}
// handle conversion of PID gains from Copter-3.3 to Copter-3.4
void Sub::convert_pid_parameters(void)
{
// conversion info
AP_Param::ConversionInfo pid_conversion_info[] = {
{ Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" },
{ Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" },
{ Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" },
{ Parameters::k_param_pid_rate_pitch, 0, AP_PARAM_FLOAT, "ATC_RAT_PIT_P" },
{ Parameters::k_param_pid_rate_pitch, 1, AP_PARAM_FLOAT, "ATC_RAT_PIT_I" },
{ Parameters::k_param_pid_rate_pitch, 2, AP_PARAM_FLOAT, "ATC_RAT_PIT_D" },
{ Parameters::k_param_pid_rate_yaw, 0, AP_PARAM_FLOAT, "ATC_RAT_YAW_P" },
{ Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" },
{ Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" },
};
AP_Param::ConversionInfo imax_conversion_info[] = {
{ Parameters::k_param_pid_rate_roll, 5, AP_PARAM_FLOAT, "ATC_RAT_RLL_IMAX" },
{ Parameters::k_param_pid_rate_pitch, 5, AP_PARAM_FLOAT, "ATC_RAT_PIT_IMAX" },
{ Parameters::k_param_pid_rate_yaw, 5, AP_PARAM_FLOAT, "ATC_RAT_YAW_IMAX" }
};
AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
{ Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" },
{ Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" },
{ Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" },
{ Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" },
{ Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" },
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" }
};
AP_Param::ConversionInfo throttle_conversion_info[] = {
{ Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" },
{ Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" }
};
// gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees
// and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
float pid_scaler = 1.27f;
// Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
if (g.frame_orientation == AP_MOTORS_X_FRAME || g.frame_orientation == AP_MOTORS_V_FRAME || g.frame_orientation == AP_MOTORS_H_FRAME) {
pid_scaler = 0.9f;
}
// scale PID gains
uint8_t table_size = ARRAY_SIZE(pid_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&pid_conversion_info[i], pid_scaler);
}
// reduce IMAX into -1 ~ +1 range
table_size = ARRAY_SIZE(imax_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&imax_conversion_info[i], 1.0f/4500.0f);
}
// convert angle controller gain and filter without scaling
table_size = ARRAY_SIZE(angle_and_filt_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&angle_and_filt_conversion_info[i], 1.0f);
}
// convert throttle parameters (multicopter only)
table_size = ARRAY_SIZE(throttle_conversion_info);
for (uint8_t i=0; i<table_size; i++) {
AP_Param::convert_old_parameter(&throttle_conversion_info[i], 0.001f);
}
} }

View File

@ -51,9 +51,7 @@ public:
// //
k_param_format_version = 0, k_param_format_version = 0,
k_param_software_type, k_param_software_type,
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
k_param_ins, // libraries/AP_InertialSensor variables k_param_ins, // libraries/AP_InertialSensor variables
k_param_NavEKF2_old, // deprecated
k_param_NavEKF2, k_param_NavEKF2,
k_param_g2, // 2nd block of parameters k_param_g2, // 2nd block of parameters
@ -69,9 +67,6 @@ public:
// relay object // relay object
k_param_relay, k_param_relay,
// EPM object
k_param_epm,
// BoardConfig object // BoardConfig object
k_param_BoardConfig, k_param_BoardConfig,
@ -89,18 +84,9 @@ public:
// Misc // Misc
// //
k_param_log_bitmask_old = 20, // Deprecated
k_param_log_last_filenumber, // *** Deprecated - remove
// with next eeprom number
// change
k_param_toy_yaw_rate, // deprecated - remove
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
k_param_rssi_pin, // unused, replaced by rssi_ library parameters
k_param_throttle_accel_enabled, // deprecated - remove
k_param_wp_yaw_behavior, k_param_wp_yaw_behavior,
k_param_acro_trainer, k_param_acro_trainer,
k_param_pilot_velocity_z_max, k_param_pilot_velocity_z_max,
k_param_circle_rate, // deprecated - remove
k_param_rangefinder_gain, k_param_rangefinder_gain,
k_param_ch8_option, k_param_ch8_option,
k_param_arming_check, k_param_arming_check,
@ -109,8 +95,6 @@ public:
k_param_gps_hdop_good, k_param_gps_hdop_good,
k_param_battery, k_param_battery,
k_param_fs_batt_mah, k_param_fs_batt_mah,
k_param_angle_rate_max, // remove
k_param_rssi_range, // unused, replaced by rssi_ library parameters
k_param_rc_feel_rp, k_param_rc_feel_rp,
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
k_param_mission, // mission library k_param_mission, // mission library
@ -120,9 +104,6 @@ public:
k_param_poshold_brake_rate, k_param_poshold_brake_rate,
k_param_poshold_brake_angle_max, k_param_poshold_brake_angle_max,
k_param_pilot_accel_z, k_param_pilot_accel_z,
k_param_serial0_baud, // deprecated - remove
k_param_serial1_baud, // deprecated - remove
k_param_serial2_baud, // deprecated - remove
k_param_land_repositioning, k_param_land_repositioning,
k_param_rangefinder, // rangefinder object k_param_rangefinder, // rangefinder object
k_param_fs_ekf_thresh, k_param_fs_ekf_thresh,
@ -130,21 +111,13 @@ public:
k_param_acro_expo, k_param_acro_expo,
k_param_throttle_deadzone, k_param_throttle_deadzone,
k_param_optflow, k_param_optflow,
k_param_dcmcheck_thresh, // deprecated - remove
k_param_log_bitmask, k_param_log_bitmask,
k_param_cli_enabled, k_param_cli_enabled,
k_param_throttle_filt, k_param_throttle_filt,
k_param_throttle_behavior, k_param_throttle_behavior,
k_param_pilot_takeoff_alt, // 64 k_param_pilot_takeoff_alt, // 64
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
k_param_gpslock_limit, // deprecated - remove
k_param_geofence_limit, // deprecated - remove
k_param_altitude_limit, // deprecated - remove
k_param_fence, k_param_fence,
k_param_gps_glitch, // deprecated
k_param_baro_glitch, // 71 - deprecated
// AP_ADSB Library // AP_ADSB Library
k_param_adsb, // 72 k_param_adsb, // 72
@ -153,28 +126,6 @@ public:
// 74: precision landing object // 74: precision landing object
k_param_precland = 74, k_param_precland = 74,
//
// 75: Singlecopter, CoaxCopter
//
k_param_single_servo_1 = 75, // remove
k_param_single_servo_2, // remove
k_param_single_servo_3, // remove
k_param_single_servo_4, // 78 - remove
//
// 80: Heli
//
k_param_heli_servo_1 = 80, // remove
k_param_heli_servo_2, // remove
k_param_heli_servo_3, // remove
k_param_heli_servo_4, // remove
k_param_heli_pitch_ff, // remove
k_param_heli_roll_ff, // remove
k_param_heli_yaw_ff, // remove
k_param_heli_stab_col_min, // remove
k_param_heli_stab_col_max, // remove
k_param_heli_servo_rsc, // 89 = full! - remove
// //
// 90: misc2 // 90: misc2
// //
@ -191,7 +142,6 @@ public:
// //
// 100: Inertial Nav // 100: Inertial Nav
// //
k_param_inertial_nav = 100, // deprecated
k_param_wp_nav, k_param_wp_nav,
k_param_attitude_control, k_param_attitude_control,
k_param_pos_control, k_param_pos_control,
@ -203,11 +153,8 @@ public:
k_param_gcs1, k_param_gcs1,
k_param_sysid_this_mav, k_param_sysid_this_mav,
k_param_sysid_my_gcs, k_param_sysid_my_gcs,
k_param_serial1_baud_old, // deprecated
k_param_telem_delay, k_param_telem_delay,
k_param_gcs2, k_param_gcs2,
k_param_serial2_baud_old, // deprecated
k_param_serial2_protocol, // deprecated
k_param_serial_manager, k_param_serial_manager,
k_param_ch9_option, k_param_ch9_option,
k_param_ch10_option, k_param_ch10_option,
@ -227,48 +174,26 @@ public:
// //
// 140: Sensor parameters // 140: Sensor parameters
// //
k_param_imu = 140, // deprecated - can be deleted
k_param_battery_monitoring = 141, // deprecated - can be deleted
k_param_volt_div_ratio, // deprecated - can be deleted
k_param_curr_amp_per_volt, // deprecated - can be deleted
k_param_input_voltage, // deprecated - can be deleted
k_param_pack_capacity, // deprecated - can be deleted
k_param_compass_enabled, k_param_compass_enabled,
k_param_compass, k_param_compass,
k_param_rangefinder_enabled_old, // deprecated
k_param_frame_orientation, k_param_frame_orientation,
k_param_optflow_enabled, // deprecated
k_param_fs_batt_voltage, k_param_fs_batt_voltage,
k_param_ch7_option, k_param_ch7_option,
k_param_auto_slew_rate, // deprecated - can be deleted
k_param_rangefinder_type_old, // deprecated
k_param_super_simple = 155, k_param_super_simple = 155,
k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change
k_param_copter_leds_mode, // deprecated - remove with next eeprom number change
k_param_ahrs, // AHRS group // 159 k_param_ahrs, // AHRS group // 159
// //
// 160: Navigation parameters // 160: Navigation parameters
// //
k_param_rtl_altitude = 160, k_param_rtl_altitude = 160,
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
k_param_rtl_loiter_time, k_param_rtl_loiter_time,
k_param_rtl_alt_final, k_param_rtl_alt_final,
k_param_tilt_comp, //164 deprecated - remove with next eeprom number change
// //
// Camera and mount parameters // Camera and mount parameters
// //
k_param_camera = 165, k_param_camera = 165,
k_param_camera_mount, k_param_camera_mount,
k_param_camera_mount2, // deprecated
//
// Batery monitoring parameters
//
k_param_battery_volt_pin = 168, // deprecated - can be deleted
k_param_battery_curr_pin, // 169 deprecated - can be deleted
// //
// 170: Radio settings // 170: Radio settings
@ -283,20 +208,14 @@ public:
k_param_rc_8, k_param_rc_8,
k_param_rc_10, k_param_rc_10,
k_param_rc_11, k_param_rc_11,
k_param_throttle_min, // remove
k_param_throttle_max, // remove
k_param_failsafe_throttle, k_param_failsafe_throttle,
k_param_throttle_fs_action, // remove
k_param_failsafe_throttle_value, k_param_failsafe_throttle_value,
k_param_throttle_trim, // remove
k_param_esc_calibrate, k_param_esc_calibrate,
k_param_radio_tuning, k_param_radio_tuning,
k_param_radio_tuning_high, k_param_radio_tuning_high,
k_param_radio_tuning_low, k_param_radio_tuning_low,
k_param_rc_speed = 192, k_param_rc_speed = 192,
k_param_failsafe_battery_enabled, k_param_failsafe_battery_enabled,
k_param_throttle_mid, // remove
k_param_failsafe_gps_enabled, // remove
k_param_rc_9, k_param_rc_9,
k_param_rc_12, k_param_rc_12,
k_param_failsafe_gcs, k_param_failsafe_gcs,
@ -316,41 +235,16 @@ public:
// //
// 210: Waypoint data // 210: Waypoint data
// //
k_param_waypoint_mode = 210, // remove
k_param_command_total, // remove
k_param_command_index, // remove
k_param_command_nav_index, // remove
k_param_waypoint_radius, // remove
k_param_circle_radius, // remove
k_param_waypoint_speed_max, // remove
k_param_land_speed, k_param_land_speed,
k_param_auto_velocity_z_min, // remove
k_param_auto_velocity_z_max, // remove - 219
k_param_land_speed_high, k_param_land_speed_high,
// //
// 220: PI/D Controllers // 220: PI/D Controllers
// //
k_param_acro_rp_p = 221, k_param_acro_rp_p = 221,
k_param_axis_lock_p, // remove
k_param_pid_rate_roll, // remove
k_param_pid_rate_pitch, // remove
k_param_pid_rate_yaw, // remove
k_param_p_stabilize_roll, // remove
k_param_p_stabilize_pitch, // remove
k_param_p_stabilize_yaw, // remove
k_param_p_pos_xy, k_param_p_pos_xy,
k_param_p_loiter_lon, // remove
k_param_pid_loiter_rate_lat, // remove
k_param_pid_loiter_rate_lon, // remove
k_param_pid_nav_lat, // remove
k_param_pid_nav_lon, // remove
k_param_p_alt_hold, k_param_p_alt_hold,
k_param_p_vel_z, k_param_p_vel_z,
k_param_pid_optflow_roll, // remove
k_param_pid_optflow_pitch, // remove
k_param_acro_balance_roll_old, // remove
k_param_acro_balance_pitch_old, // remove
k_param_pid_accel_z, k_param_pid_accel_z,
k_param_acro_balance_roll, k_param_acro_balance_roll,
k_param_acro_balance_pitch, k_param_acro_balance_pitch,

View File

@ -117,7 +117,6 @@ void Sub::init_ardupilot()
#endif #endif
// initialise notify system // initialise notify system
// disable external leds if epm is enabled because of pin conflict on the APM
notify.init(true); notify.init(true);
// initialise battery monitor // initialise battery monitor