Copter: Convert PRX_ parameters to PRX1_

This commit is contained in:
rishabsingh3003 2022-08-21 22:56:44 +05:30 committed by Andrew Tridgell
parent b0108f2c0c
commit 8fcd42d104
3 changed files with 34 additions and 0 deletions

View File

@ -855,6 +855,9 @@ private:
// Parameters.cpp // Parameters.cpp
void load_parameters(void) override; void load_parameters(void) override;
void convert_pid_parameters(void); void convert_pid_parameters(void);
#if HAL_PROXIMITY_ENABLED
void convert_prx_parameters();
#endif
void convert_lgr_parameters(void); void convert_lgr_parameters(void);
void convert_tradheli_parameters(void) const; void convert_tradheli_parameters(void) const;
void convert_fs_options_params(void) const; void convert_fs_options_params(void) const;

View File

@ -1514,6 +1514,32 @@ void Copter::convert_pid_parameters(void)
SRV_Channels::upgrade_parameters(); SRV_Channels::upgrade_parameters();
} }
#if HAL_PROXIMITY_ENABLED
void Copter::convert_prx_parameters()
{
// convert PRX to PRX1_ parameters for Copter-4.3
// PARAMETER_CONVERSION - Added: Aug-2022
const AP_Param::ConversionInfo prx_conversion_info[] = {
{ Parameters::k_param_g2, 72, AP_PARAM_INT8, "PRX1_TYPE" },
{ Parameters::k_param_g2, 136, AP_PARAM_INT8, "PRX1_ORIENT" },
{ Parameters::k_param_g2, 200, AP_PARAM_INT16, "PRX1_YAW_CORR" },
{ Parameters::k_param_g2, 264, AP_PARAM_INT16, "PRX1_IGN_ANG1" },
{ Parameters::k_param_g2, 328, AP_PARAM_INT8, "PRX1_IGN_WID1" },
{ Parameters::k_param_g2, 392, AP_PARAM_INT16, "PRX1_IGN_ANG2" },
{ Parameters::k_param_g2, 456, AP_PARAM_INT8, "PRX1_IGN_WID2" },
{ Parameters::k_param_g2, 520, AP_PARAM_INT16, "PRX1_IGN_ANG3" },
{ Parameters::k_param_g2, 584, AP_PARAM_INT8, "PRX1_IGN_WID3" },
{ Parameters::k_param_g2, 648, AP_PARAM_INT16, "PRX1_IGN_ANG4" },
{ Parameters::k_param_g2, 712, AP_PARAM_INT8, "PRX1_IGN_WID4" },
{ Parameters::k_param_g2, 1224, AP_PARAM_FLOAT, "PRX1_MIN" },
{ Parameters::k_param_g2, 1288, AP_PARAM_FLOAT, "PRX1_MAX" },
};
for (const auto &info : prx_conversion_info) {
AP_Param::convert_old_parameter(&info, 1.0);
}
}
#endif
#if LANDING_GEAR_ENABLED == ENABLED #if LANDING_GEAR_ENABLED == ENABLED
/* /*
convert landing gear parameters convert landing gear parameters

View File

@ -521,6 +521,11 @@ void Copter::allocate_motors(void)
convert_tradheli_parameters(); convert_tradheli_parameters();
#endif #endif
#if HAL_PROXIMITY_ENABLED
// convert PRX to PRX1_ parameters
convert_prx_parameters();
#endif
// param count could have changed // param count could have changed
AP_Param::invalidate_count(); AP_Param::invalidate_count();
} }