Copter: remove stale parameter conversions
this removes stale parameter conversions. These patches are all in the Copter-4.0.0 tag, meaning that they are all for upgrading from a version prior to that to a version prior-or-equal-to Copter-4.0.0 Past this a user running a version of ArduCopter < 4.0.0 to something >= 4.7.0 will not have smooth parameter conversions
This commit is contained in:
parent
7e8aab1ae8
commit
e202a4128c
@ -968,7 +968,6 @@ private:
|
|||||||
void convert_prx_parameters();
|
void convert_prx_parameters();
|
||||||
#endif
|
#endif
|
||||||
void convert_lgr_parameters(void);
|
void convert_lgr_parameters(void);
|
||||||
void convert_tradheli_parameters(void) const;
|
|
||||||
|
|
||||||
// precision_landing.cpp
|
// precision_landing.cpp
|
||||||
void init_precland();
|
void init_precland();
|
||||||
|
@ -1316,53 +1316,10 @@ ParametersG2::ParametersG2(void) :
|
|||||||
AP_Param::setup_object_defaults(this, var_info2);
|
AP_Param::setup_object_defaults(this, var_info2);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
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[] = {
|
|
||||||
// PARAMETER_CONVERSION - Added: Jan-2017
|
|
||||||
{ Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" },
|
|
||||||
// battery
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2018
|
|
||||||
{ Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" },
|
|
||||||
{ Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" },
|
|
||||||
{ Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" },
|
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Aug-2018
|
|
||||||
{ 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" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Apr-2019
|
|
||||||
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Jul-2019
|
|
||||||
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
|
|
||||||
};
|
|
||||||
|
|
||||||
void Copter::load_parameters(void)
|
void Copter::load_parameters(void)
|
||||||
{
|
{
|
||||||
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
|
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
|
||||||
|
|
||||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
|
||||||
|
|
||||||
#if AP_LANDINGGEAR_ENABLED
|
|
||||||
// convert landing gear parameters
|
|
||||||
// PARAMETER_CONVERSION - Added: Nov-2018
|
|
||||||
convert_lgr_parameters();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if MODE_RTL_ENABLED
|
#if MODE_RTL_ENABLED
|
||||||
// PARAMETER_CONVERSION - Added: Sep-2021
|
// PARAMETER_CONVERSION - Added: Sep-2021
|
||||||
g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16);
|
g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16);
|
||||||
@ -1413,48 +1370,14 @@ void Copter::load_parameters(void)
|
|||||||
void Copter::convert_pid_parameters(void)
|
void Copter::convert_pid_parameters(void)
|
||||||
{
|
{
|
||||||
const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
|
const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = {
|
||||||
// PARAMETER_CONVERSION - Added: Jan-2018
|
|
||||||
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" },
|
|
||||||
{ Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" },
|
|
||||||
{ Parameters::k_param_pi_vel_xy, 1, AP_PARAM_FLOAT, "PSC_VELXY_I" },
|
|
||||||
{ Parameters::k_param_pi_vel_xy, 2, AP_PARAM_FLOAT, "PSC_VELXY_IMAX" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Aug-2021
|
// PARAMETER_CONVERSION - Added: Aug-2021
|
||||||
{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FLTE" },
|
{ Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FLTE" },
|
||||||
// PARAMETER_CONVERSION - Added: Jan-2018
|
|
||||||
{ Parameters::k_param_p_vel_z, 0, AP_PARAM_FLOAT, "PSC_VELZ_P" },
|
|
||||||
{ Parameters::k_param_pid_accel_z, 0, AP_PARAM_FLOAT, "PSC_ACCZ_P" },
|
|
||||||
{ Parameters::k_param_pid_accel_z, 1, AP_PARAM_FLOAT, "PSC_ACCZ_I" },
|
|
||||||
{ Parameters::k_param_pid_accel_z, 2, AP_PARAM_FLOAT, "PSC_ACCZ_D" },
|
|
||||||
{ Parameters::k_param_pid_accel_z, 5, AP_PARAM_FLOAT, "PSC_ACCZ_IMAX" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Oct-2019
|
|
||||||
{ Parameters::k_param_pid_accel_z, 6, AP_PARAM_FLOAT, "PSC_ACCZ_FLTE" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Jan-2018
|
|
||||||
{ Parameters::k_param_p_alt_hold, 0, AP_PARAM_FLOAT, "PSC_POSZ_P" },
|
|
||||||
{ Parameters::k_param_p_pos_xy, 0, AP_PARAM_FLOAT, "PSC_POSXY_P" },
|
|
||||||
};
|
|
||||||
const AP_Param::ConversionInfo loiter_conversion_info[] = {
|
|
||||||
// PARAMETER_CONVERSION - Added: Apr-2018
|
|
||||||
{ Parameters::k_param_wp_nav, 4, AP_PARAM_FLOAT, "LOIT_SPEED" },
|
|
||||||
{ Parameters::k_param_wp_nav, 7, AP_PARAM_FLOAT, "LOIT_BRK_JERK" },
|
|
||||||
{ Parameters::k_param_wp_nav, 8, AP_PARAM_FLOAT, "LOIT_ACC_MAX" },
|
|
||||||
{ Parameters::k_param_wp_nav, 9, AP_PARAM_FLOAT, "LOIT_BRK_ACCEL" }
|
|
||||||
};
|
};
|
||||||
|
|
||||||
// convert angle controller gain and filter without scaling
|
// convert angle controller gain and filter without scaling
|
||||||
for (const auto &info : angle_and_filt_conversion_info) {
|
for (const auto &info : angle_and_filt_conversion_info) {
|
||||||
AP_Param::convert_old_parameter(&info, 1.0f);
|
AP_Param::convert_old_parameter(&info, 1.0f);
|
||||||
}
|
}
|
||||||
// convert RC_FEEL_RP to ATC_INPUT_TC
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2018
|
|
||||||
const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" };
|
|
||||||
AP_Int8 rc_feel_rp_old;
|
|
||||||
if (AP_Param::find_old_parameter(&rc_feel_rp_conversion_info, &rc_feel_rp_old)) {
|
|
||||||
AP_Param::set_default_by_name(rc_feel_rp_conversion_info.new_name, (1.0f / (2.0f + rc_feel_rp_old.get() * 0.1f)));
|
|
||||||
}
|
|
||||||
// convert loiter parameters
|
|
||||||
for (const auto &info : loiter_conversion_info) {
|
|
||||||
AP_Param::convert_old_parameter(&info, 1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
// TradHeli default parameters
|
// TradHeli default parameters
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
@ -1480,36 +1403,7 @@ void Copter::convert_pid_parameters(void)
|
|||||||
{ "ATC_RAT_PIT_ILMI", 0.05},
|
{ "ATC_RAT_PIT_ILMI", 0.05},
|
||||||
};
|
};
|
||||||
AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));
|
AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));
|
||||||
#endif
|
#endif // FRAME_CONFIG == HELI_FRAME
|
||||||
|
|
||||||
// attitude and position control filter parameter changes (from _FILT to FLTD, FLTE, FLTT) for Copter-4.0
|
|
||||||
// magic numbers shown below are discovered by setting AP_PARAM_KEY_DUMP = 1
|
|
||||||
const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = {
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
// tradheli moves ATC_RAT_RLL/PIT_FILT to FLTE, ATC_RAT_YAW_FILT to FLTE
|
|
||||||
// PARAMETER_CONVERSION - Added: Jul-2019
|
|
||||||
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },
|
|
||||||
{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },
|
|
||||||
{ Parameters::k_param_attitude_control, 388, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },
|
|
||||||
#else
|
|
||||||
// multicopters move ATC_RAT_RLL/PIT_FILT to FLTD & FLTT, ATC_RAT_YAW_FILT to FLTE
|
|
||||||
{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTD" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Oct-2019
|
|
||||||
{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTT" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Jul-2019
|
|
||||||
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTD" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Oct-2019
|
|
||||||
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTT" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Jul-2019
|
|
||||||
{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },
|
|
||||||
{ Parameters::k_param_attitude_control, 449, AP_PARAM_FLOAT, "ATC_RAT_RLL_FF" },
|
|
||||||
{ Parameters::k_param_attitude_control, 450, AP_PARAM_FLOAT, "ATC_RAT_PIT_FF" },
|
|
||||||
{ Parameters::k_param_attitude_control, 451, AP_PARAM_FLOAT, "ATC_RAT_YAW_FF" },
|
|
||||||
#endif
|
|
||||||
// PARAMETER_CONVERSION - Added: Oct-2019
|
|
||||||
{ Parameters::k_param_pos_control, 388, AP_PARAM_FLOAT, "PSC_ACCZ_FLTE" },
|
|
||||||
};
|
|
||||||
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[0], ARRAY_SIZE(ff_and_filt_conversion_info));
|
|
||||||
|
|
||||||
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
|
||||||
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
|
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
|
||||||
@ -1582,275 +1476,3 @@ void Copter::convert_prx_parameters()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_LANDINGGEAR_ENABLED
|
|
||||||
/*
|
|
||||||
convert landing gear parameters
|
|
||||||
*/
|
|
||||||
void Copter::convert_lgr_parameters(void)
|
|
||||||
{
|
|
||||||
// PARAMETER_CONVERSION - Added: Nov-2018
|
|
||||||
|
|
||||||
// convert landing gear PWM values
|
|
||||||
uint8_t chan;
|
|
||||||
if (!SRV_Channels::find_channel(SRV_Channel::k_landing_gear_control, chan)) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
// parameter names are 1 based
|
|
||||||
chan += 1;
|
|
||||||
|
|
||||||
char pname[17];
|
|
||||||
AP_Int16 *servo_min, *servo_max, *servo_trim;
|
|
||||||
AP_Int16 *servo_reversed;
|
|
||||||
|
|
||||||
enum ap_var_type ptype;
|
|
||||||
// get pointers to the servo min, max and trim parameters
|
|
||||||
snprintf(pname, sizeof(pname), "SERVO%u_MIN", chan);
|
|
||||||
servo_min = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
|
||||||
|
|
||||||
snprintf(pname, sizeof(pname), "SERVO%u_MAX", chan);
|
|
||||||
servo_max = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
|
||||||
|
|
||||||
snprintf(pname, sizeof(pname), "SERVO%u_TRIM", chan);
|
|
||||||
servo_trim = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
|
||||||
|
|
||||||
snprintf(pname, sizeof(pname), "SERVO%u_REVERSED", chan & 0x3F); // Only use the 6 LSBs, avoids a cpp warning
|
|
||||||
servo_reversed = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
|
||||||
|
|
||||||
if (!servo_min || !servo_max || !servo_trim || !servo_reversed) {
|
|
||||||
// this shouldn't happen
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (servo_min->configured() ||
|
|
||||||
servo_max->configured() ||
|
|
||||||
servo_trim->configured() ||
|
|
||||||
servo_reversed->configured()) {
|
|
||||||
// has been previously saved, don't upgrade
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// get the old PWM values
|
|
||||||
AP_Int16 old_pwm;
|
|
||||||
uint16_t old_retract=0, old_deploy=0;
|
|
||||||
const AP_Param::ConversionInfo cinfo_ret { Parameters::k_param_landinggear, 0, AP_PARAM_INT16, nullptr };
|
|
||||||
const AP_Param::ConversionInfo cinfo_dep { Parameters::k_param_landinggear, 1, AP_PARAM_INT16, nullptr };
|
|
||||||
if (AP_Param::find_old_parameter(&cinfo_ret, &old_pwm)) {
|
|
||||||
old_retract = (uint16_t)old_pwm.get();
|
|
||||||
}
|
|
||||||
if (AP_Param::find_old_parameter(&cinfo_dep, &old_pwm)) {
|
|
||||||
old_deploy = (uint16_t)old_pwm.get();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (old_retract == 0 && old_deploy == 0) {
|
|
||||||
// old parameters were never set
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// use old defaults
|
|
||||||
if (old_retract == 0) {
|
|
||||||
old_retract = 1250;
|
|
||||||
}
|
|
||||||
if (old_deploy == 0) {
|
|
||||||
old_deploy = 1750;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set and save correct values on the servo
|
|
||||||
if (old_retract <= old_deploy) {
|
|
||||||
servo_max->set_and_save(old_deploy);
|
|
||||||
servo_min->set_and_save(old_retract);
|
|
||||||
servo_trim->set_and_save(old_retract);
|
|
||||||
servo_reversed->set_and_save_ifchanged(0);
|
|
||||||
} else {
|
|
||||||
servo_max->set_and_save(old_retract);
|
|
||||||
servo_min->set_and_save(old_deploy);
|
|
||||||
servo_trim->set_and_save(old_deploy);
|
|
||||||
servo_reversed->set_and_save_ifchanged(1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
// handle conversion of tradheli parameters from Copter-3.6 to Copter-3.7
|
|
||||||
void Copter::convert_tradheli_parameters(void) const
|
|
||||||
{
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2019
|
|
||||||
if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) {
|
|
||||||
// single heli conversion info
|
|
||||||
const AP_Param::ConversionInfo singleheli_conversion_info[] = {
|
|
||||||
{ Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW_H3_SV1_POS" },
|
|
||||||
{ Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW_H3_SV2_POS" },
|
|
||||||
{ Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW_H3_SV3_POS" },
|
|
||||||
{ Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW_H3_PHANG" },
|
|
||||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW_COL_DIR" },
|
|
||||||
};
|
|
||||||
|
|
||||||
// convert single heli parameters without scaling
|
|
||||||
uint8_t table_size = ARRAY_SIZE(singleheli_conversion_info);
|
|
||||||
for (uint8_t i=0; i<table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameter(&singleheli_conversion_info[i], 1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
// convert to known swash type for setups that match
|
|
||||||
// PARAMETER_CONVERSION - Added: Sep-2019
|
|
||||||
AP_Int16 swash_pos_1, swash_pos_2, swash_pos_3, swash_phang;
|
|
||||||
AP_Int8 swash_type;
|
|
||||||
bool swash_pos1_exist = AP_Param::find_old_parameter(&singleheli_conversion_info[0], &swash_pos_1);
|
|
||||||
bool swash_pos2_exist = AP_Param::find_old_parameter(&singleheli_conversion_info[1], &swash_pos_2);
|
|
||||||
bool swash_pos3_exist = AP_Param::find_old_parameter(&singleheli_conversion_info[2], &swash_pos_3);
|
|
||||||
bool swash_phang_exist = AP_Param::find_old_parameter(&singleheli_conversion_info[3], &swash_phang);
|
|
||||||
const AP_Param::ConversionInfo swash_type_info { Parameters::k_param_motors, 5, AP_PARAM_INT8, "H_SW_TYPE" };
|
|
||||||
bool swash_type_exists = AP_Param::find_old_parameter(&swash_type_info, &swash_type);
|
|
||||||
|
|
||||||
if (swash_type_exists) {
|
|
||||||
// convert swash type to new parameter
|
|
||||||
AP_Param::convert_old_parameter(&swash_type_info, 1.0f);
|
|
||||||
} else {
|
|
||||||
// old swash type is not in eeprom and thus type is default value of generic swash
|
|
||||||
if (swash_pos1_exist || swash_pos2_exist || swash_pos3_exist || swash_phang_exist) {
|
|
||||||
// if any params exist with the generic swash then the upgraded swash type must be generic
|
|
||||||
// find the new variable in the variable structures
|
|
||||||
enum ap_var_type ptype;
|
|
||||||
AP_Param *ap2;
|
|
||||||
ap2 = AP_Param::find("H_SW_TYPE", &ptype);
|
|
||||||
// make sure the pointer is valid
|
|
||||||
if (ap2 != nullptr) {
|
|
||||||
// see if we can load it from EEPROM
|
|
||||||
if (!ap2->configured()) {
|
|
||||||
// the new parameter is not in storage so set generic swash
|
|
||||||
AP_Param::set_and_save_by_name("H_SW_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL) {
|
|
||||||
// dual heli conversion info
|
|
||||||
const AP_Param::ConversionInfo dualheli_conversion_info[] = {
|
|
||||||
{ Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW_H3_SV1_POS" },
|
|
||||||
{ Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW_H3_SV2_POS" },
|
|
||||||
{ Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW_H3_SV3_POS" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2019
|
|
||||||
{ Parameters::k_param_motors, 4, AP_PARAM_INT16, "H_SW2_H3_SV1_POS" },
|
|
||||||
{ Parameters::k_param_motors, 5, AP_PARAM_INT16, "H_SW2_H3_SV2_POS" },
|
|
||||||
{ Parameters::k_param_motors, 6, AP_PARAM_INT16, "H_SW2_H3_SV3_POS" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Sep-2019
|
|
||||||
{ Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW_H3_PHANG" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2019
|
|
||||||
{ Parameters::k_param_motors, 8, AP_PARAM_INT16, "H_SW2_H3_PHANG" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Sep-2019
|
|
||||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW_COL_DIR" },
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2019
|
|
||||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW2_COL_DIR" },
|
|
||||||
};
|
|
||||||
|
|
||||||
// convert dual heli parameters without scaling
|
|
||||||
uint8_t table_size = ARRAY_SIZE(dualheli_conversion_info);
|
|
||||||
for (uint8_t i=0; i<table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameter(&dualheli_conversion_info[i], 1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Sep-2019
|
|
||||||
|
|
||||||
// convert to known swash type for setups that match
|
|
||||||
AP_Int16 swash1_pos_1, swash1_pos_2, swash1_pos_3, swash1_phang, swash2_pos_1, swash2_pos_2, swash2_pos_3, swash2_phang;
|
|
||||||
bool swash1_pos1_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[0], &swash1_pos_1);
|
|
||||||
bool swash1_pos2_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[1], &swash1_pos_2);
|
|
||||||
bool swash1_pos3_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[2], &swash1_pos_3);
|
|
||||||
bool swash1_phang_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[6], &swash1_phang);
|
|
||||||
bool swash2_pos1_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[3], &swash2_pos_1);
|
|
||||||
bool swash2_pos2_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[4], &swash2_pos_2);
|
|
||||||
bool swash2_pos3_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[5], &swash2_pos_3);
|
|
||||||
bool swash2_phang_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[7], &swash2_phang);
|
|
||||||
|
|
||||||
// SWASH 1
|
|
||||||
// old swash type is not in eeprom and thus type is default value of generic swash
|
|
||||||
if (swash1_pos1_exist || swash1_pos2_exist || swash1_pos3_exist || swash1_phang_exist) {
|
|
||||||
// if any params exist with the generic swash then the upgraded swash type must be generic
|
|
||||||
// find the new variable in the variable structures
|
|
||||||
enum ap_var_type ptype;
|
|
||||||
AP_Param *ap2;
|
|
||||||
ap2 = AP_Param::find("H_SW_TYPE", &ptype);
|
|
||||||
// make sure the pointer is valid
|
|
||||||
if (ap2 != nullptr) {
|
|
||||||
// see if we can load it from EEPROM
|
|
||||||
if (!ap2->configured()) {
|
|
||||||
// the new parameter is not in storage so set generic swash
|
|
||||||
AP_Param::set_and_save_by_name("H_SW_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
//SWASH 2
|
|
||||||
// old swash type is not in eeprom and thus type is default value of generic swash
|
|
||||||
if (swash2_pos1_exist || swash2_pos2_exist || swash2_pos3_exist || swash2_phang_exist) {
|
|
||||||
// if any params exist with the generic swash then the upgraded swash type must be generic
|
|
||||||
// find the new variable in the variable structures
|
|
||||||
enum ap_var_type ptype;
|
|
||||||
AP_Param *ap2;
|
|
||||||
ap2 = AP_Param::find("H_SW2_TYPE", &ptype);
|
|
||||||
// make sure the pointer is valid
|
|
||||||
if (ap2 != nullptr) {
|
|
||||||
// see if we can load it from EEPROM
|
|
||||||
if (!ap2->configured()) {
|
|
||||||
// the new parameter is not in storage so set generic swash
|
|
||||||
AP_Param::set_and_save_by_name("H_SW2_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// table of rsc parameters to be converted with scaling
|
|
||||||
const AP_Param::ConversionInfo rschelipct_conversion_info[] = {
|
|
||||||
{ Parameters::k_param_motors, 1280, AP_PARAM_INT16, "H_RSC_THRCRV_0" },
|
|
||||||
{ Parameters::k_param_motors, 1344, AP_PARAM_INT16, "H_RSC_THRCRV_25" },
|
|
||||||
{ Parameters::k_param_motors, 1408, AP_PARAM_INT16, "H_RSC_THRCRV_50" },
|
|
||||||
{ Parameters::k_param_motors, 1472, AP_PARAM_INT16, "H_RSC_THRCRV_75" },
|
|
||||||
{ Parameters::k_param_motors, 1536, AP_PARAM_INT16, "H_RSC_THRCRV_100" },
|
|
||||||
{ Parameters::k_param_motors, 448, AP_PARAM_INT16, "H_RSC_SETPOINT" },
|
|
||||||
{ Parameters::k_param_motors, 768, AP_PARAM_INT16, "H_RSC_CRITICAL" },
|
|
||||||
{ Parameters::k_param_motors, 832, AP_PARAM_INT16, "H_RSC_IDLE" },
|
|
||||||
};
|
|
||||||
// convert heli rsc parameters with scaling
|
|
||||||
uint8_t table_size = ARRAY_SIZE(rschelipct_conversion_info);
|
|
||||||
for (uint8_t i=0; i<table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameter(&rschelipct_conversion_info[i], 0.1f);
|
|
||||||
}
|
|
||||||
|
|
||||||
// table of rsc parameters to be converted without scaling
|
|
||||||
const AP_Param::ConversionInfo rscheli_conversion_info[] = {
|
|
||||||
{ Parameters::k_param_motors, 512, AP_PARAM_INT8, "H_RSC_MODE" },
|
|
||||||
{ Parameters::k_param_motors, 640, AP_PARAM_INT8, "H_RSC_RAMP_TIME" },
|
|
||||||
{ Parameters::k_param_motors, 704, AP_PARAM_INT8, "H_RSC_RUNUP_TIME" },
|
|
||||||
{ Parameters::k_param_motors, 1216, AP_PARAM_INT16,"H_RSC_SLEWRATE" },
|
|
||||||
};
|
|
||||||
// convert heli rsc parameters without scaling
|
|
||||||
table_size = ARRAY_SIZE(rscheli_conversion_info);
|
|
||||||
for (uint8_t i=0; i<table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameter(&rscheli_conversion_info[i], 1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
// update tail speed parameter with scaling
|
|
||||||
AP_Int16 *tailspeed;
|
|
||||||
enum ap_var_type ptype;
|
|
||||||
tailspeed = (AP_Int16 *)AP_Param::find("H_TAIL_SPEED", &ptype);
|
|
||||||
if (tailspeed != nullptr && tailspeed->get() > 100 ) {
|
|
||||||
uint16_t tailspeed_pct = (uint16_t)(0.1f * tailspeed->get());
|
|
||||||
AP_Param::set_and_save_by_name("H_TAIL_SPEED", tailspeed_pct );
|
|
||||||
}
|
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Dec-2019
|
|
||||||
// table of stabilize collective parameters to be converted with scaling
|
|
||||||
const AP_Param::ConversionInfo collhelipct_conversion_info[] = {
|
|
||||||
{ Parameters::k_param_input_manager, 1, AP_PARAM_INT16, "IM_STB_COL_1" },
|
|
||||||
{ Parameters::k_param_input_manager, 2, AP_PARAM_INT16, "IM_STB_COL_2" },
|
|
||||||
{ Parameters::k_param_input_manager, 3, AP_PARAM_INT16, "IM_STB_COL_3" },
|
|
||||||
{ Parameters::k_param_input_manager, 4, AP_PARAM_INT16, "IM_STB_COL_4" },
|
|
||||||
};
|
|
||||||
|
|
||||||
// convert stabilize collective parameters with scaling
|
|
||||||
table_size = ARRAY_SIZE(collhelipct_conversion_info);
|
|
||||||
for (uint8_t i=0; i<table_size; i++) {
|
|
||||||
AP_Param::convert_old_parameter(&collhelipct_conversion_info[i], 0.1f);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
@ -507,7 +507,6 @@ void Copter::allocate_motors(void)
|
|||||||
// upgrade parameters. This must be done after allocating the objects
|
// upgrade parameters. This must be done after allocating the objects
|
||||||
convert_pid_parameters();
|
convert_pid_parameters();
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
convert_tradheli_parameters();
|
|
||||||
motors->heli_motors_param_conversions();
|
motors->heli_motors_param_conversions();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user