diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 4eb3db11691f5..5be95dedf7dde 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -588,17 +588,17 @@ void Tracker::load_parameters(void) #if AP_STATS_ENABLED // PARAMETER_CONVERSION - Added: Jan-2024 - AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, true); #endif #if AP_SCRIPTING_ENABLED // PARAMETER_CONVERSION - Added: Jan-2024 - AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, true); #endif // PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6 #if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif #if HAL_HAVE_SAFETY_SWITCH diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index fcde858fc4b6d..8a1cec0c3ab00 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1354,56 +1354,29 @@ void Copter::load_parameters(void) // PARAMETER_CONVERSION - Added: Mar-2022 #if AP_FENCE_ENABLED - AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true); #endif - // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + static const AP_Param::G2ObjectConversion g2_conversions[] { #if AP_STATS_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 12; // Old parameter index in g2 - const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false); - } -#endif // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + { &stats, stats.var_info, 12 }, +#endif #if AP_SCRIPTING_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 30; // Old parameter index in g2 - const uint16_t old_top_element = 94; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &scripting, scripting.var_info, old_index, old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + { &scripting, scripting.var_info, 30 }, #endif - +#if AP_GRIPPER_ENABLED // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 -#if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + { &gripper, gripper.var_info, 13 }, #endif + }; - // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 -#if AP_GRIPPER_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } + AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions)); - const uint16_t old_index = 13; // Old parameter index in g2 - const uint16_t old_top_element = 4045; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &gripper, gripper.var_info, old_index, old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 +#if HAL_LOGGING_ENABLED + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif // setup AP_Param frame type flags diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index fe571b2b58293..b6db6ba4ae6f9 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1468,29 +1468,12 @@ void Plane::load_parameters(void) g.use_reverse_thrust.convert_parameter_width(AP_PARAM_INT16); - - // PARAMETER_CONVERSION - Added: Oct-2021 -#if HAL_EFI_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 22; // Old parameter index in g2 - const uint16_t old_top_element = 86; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &efi, efi.var_info, old_index, old_top_element, false); - } -#endif - #if AP_AIRSPEED_ENABLED // PARAMETER_CONVERSION - Added: Jan-2022 { const uint16_t old_key = g.k_param_airspeed; const uint16_t old_index = 0; // Old parameter index in the tree - const uint16_t old_top_element = 0; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, old_top_element, true); + AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, true); } #endif @@ -1511,7 +1494,7 @@ void Plane::load_parameters(void) // PARAMETER_CONVERSION - Added: Mar-2022 #if AP_FENCE_ENABLED - AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, true); #endif // PARAMETER_CONVERSION - Added: Dec 2023 @@ -1527,52 +1510,29 @@ void Plane::load_parameters(void) landing.convert_parameters(); - // PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6 -#if AP_STATS_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 5; // Old parameter index in g2 - const uint16_t old_top_element = 4037; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false); - } + static const AP_Param::G2ObjectConversion g2_conversions[] { + // PARAMETER_CONVERSION - Added: Oct-2021 +#if HAL_EFI_ENABLED + { &efi, efi.var_info, 22 }, #endif +#if AP_STATS_ENABLED // PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6 + { &stats, stats.var_info, 5 }, +#endif #if AP_SCRIPTING_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 14; // Old parameter index in g2 - const uint16_t old_top_element = 78; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &scripting, scripting.var_info, old_index, old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6 + { &scripting, scripting.var_info, 14 }, #endif - - // PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6 #if AP_GRIPPER_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 12; // Old parameter index in g2 - const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &gripper, gripper.var_info, old_index, old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6 + { &gripper, gripper.var_info, 12 }, #endif + }; + + AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions)); // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 #if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif } diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 8d0fd2ef9792e..d10ffe1e18333 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -741,72 +741,35 @@ void Sub::load_parameters() // We should ignore this parameter since ROVs are neutral buoyancy AP_Param::set_by_name("MOT_THST_HOVER", 0.5); -// PARAMETER_CONVERSION - Added: JAN-2022 -#if AP_AIRSPEED_ENABLED - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 19; // Old parameter index in the tree - const uint16_t old_top_element = 4051; // Old group element in the tree for the first subgroup element - AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false); -#endif - - // PARAMETER_CONVERSION - Added: Mar-2022 #if AP_FENCE_ENABLED - AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, true); #endif - // PARAMETER_CONVERSION - Added: Jan-2024 -#if AP_STATS_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo stats_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, stats_info.old_key)) { - return; - } - - const uint16_t stats_old_index = 1; // Old parameter index in g2 - const uint16_t stats_old_top_element = 4033; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(stats_info.old_key, &stats, stats.var_info, stats_old_index, stats_old_top_element, false); - } + static const AP_Param::G2ObjectConversion g2_conversions[] { +#if AP_AIRSPEED_ENABLED + // PARAMETER_CONVERSION - Added: JAN-2022 + { &airspeed, airspeed.var_info, 19 }, #endif +#if AP_STATS_ENABLED // PARAMETER_CONVERSION - Added: Jan-2024 + { &stats, stats.var_info, 1 }, +#endif #if AP_SCRIPTING_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo scripting_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, scripting_info.old_key)) { - return; - } - - const uint16_t scripting_old_index = 18; // Old parameter index in g2 - const uint16_t scripting_old_top_element = 82; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Jan-2024 + { &scripting, scripting.var_info, 18 }, #endif - - // PARAMETER_CONVERSION - Added: Feb-2024 #if AP_GRIPPER_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo gripper_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, gripper_info.old_key)) { - return; - } - - const uint16_t old_gripper_index = 3; // Old parameter index in g2 - const uint16_t old_gripper_top_element = 4035; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(gripper_info.old_key, &gripper, gripper.var_info, old_gripper_index, old_gripper_top_element, false); - } + // PARAMETER_CONVERSION - Added: Feb-2024 + { &gripper, gripper.var_info, 3 }, #endif + }; + + AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions)); // PARAMETER_CONVERSION - Added: Feb-2024 #if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif } diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index cbc14fc4101a2..f9f11e44f0066 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -842,38 +842,21 @@ void Blimp::load_parameters(void) { AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version); - // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + static const AP_Param::G2ObjectConversion g2_conversions[] { #if AP_STATS_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 12; // Old parameter index in g2 - const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false); - } -#endif // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + { &stats, stats.var_info, 12 }, +#endif #if AP_SCRIPTING_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { - return; - } - - const uint16_t old_index = 30; // Old parameter index in g2 - const uint16_t old_top_element = 94; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(info.old_key, &scripting, scripting.var_info, old_index, old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 + { &scripting, scripting.var_info, 30 }, #endif + }; + AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions)); // PARAMETER_CONVERSION - Added: Feb-2024 #if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif // setup AP_Param frame type flags diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 7a4d0e312eb50..5f24887181c8c 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -875,70 +875,38 @@ void Rover::load_parameters(void) } #endif -// PARAMETER_CONVERSION - Added: JAN-2022 + static const AP_Param::G2ObjectConversion g2_conversions[] { #if AP_AIRSPEED_ENABLED - const uint16_t old_index = 37; // Old parameter index in the tree - const uint16_t old_top_element = 4069; // Old group element in the tree for the first subgroup element - AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false); +// PARAMETER_CONVERSION - Added: JAN-2022 + { &airspeed, airspeed.var_info, 37 }, #endif - -// PARAMETER_CONVERSION - Added: MAR-2022 #if AP_AIS_ENABLED - AP_Param::convert_class(info.old_key, &ais, ais.var_info, 50, 114, false); +// PARAMETER_CONVERSION - Added: MAR-2022 + { &ais, ais.var_info, 50 }, #endif - -// PARAMETER_CONVERSION - Added: Mar-2022 #if AP_FENCE_ENABLED - AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false); +// PARAMETER_CONVERSION - Added: Mar-2022 + { &fence, fence.var_info, 17 }, #endif - - // PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6 #if AP_STATS_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo stats_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, stats_info.old_key)) { - return; - } - - const uint16_t stats_old_index = 1; // Old parameter index in g2 - const uint16_t stats_old_top_element = 4033; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(stats_info.old_key, &stats, stats.var_info, stats_old_index, stats_old_top_element, false); - } -#endif // PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6 + { &stats, stats.var_info, 1 }, +#endif #if AP_SCRIPTING_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo scripting_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, scripting_info.old_key)) { - return; - } - - const uint16_t scripting_old_index = 41; // Old parameter index in g2 - const uint16_t scripting_old_top_element = 105; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6 + { &scripting, scripting.var_info, 41 }, #endif - - // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 #if AP_GRIPPER_ENABLED - { - // Find G2's Top Level Key - AP_Param::ConversionInfo gripper_info; - if (!AP_Param::find_top_level_key_by_pointer(&g2, gripper_info.old_key)) { - return; - } - - const uint16_t gripper_old_index = 39; // Old parameter index in g2 - const uint16_t gripper_old_top_element = 4071; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) - AP_Param::convert_class(gripper_info.old_key, &gripper, gripper.var_info, gripper_old_index, gripper_old_top_element, false); - } + // PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6 + { &gripper, gripper.var_info, 39 }, #endif + }; + + AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions)); // PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6 #if HAL_LOGGING_ENABLED - AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true); + AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true); #endif } diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 996960a0b5819..cb313ed283cb6 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2033,7 +2033,7 @@ void AP_Param::convert_old_parameters_scaled(const struct ConversionInfo *conver // is_top_level: Is true if the class had its own top level key, param_key. It is false if the class was a subgroup void AP_Param::convert_class(uint16_t param_key, void *object_pointer, const struct AP_Param::GroupInfo *group_info, - uint16_t old_index, uint16_t old_top_element, bool is_top_level) + uint16_t old_index, bool is_top_level) { const uint8_t group_shift = is_top_level ? 0 : 6; @@ -2074,6 +2074,20 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer, flush(); } +void AP_Param::convert_g2_objects(const void *g2, const G2ObjectConversion g2_conversions[], uint8_t num_conversions) +{ + // Find G2's Top Level Key + ConversionInfo info; + if (!find_top_level_key_by_pointer(g2, info.old_key)) { + return; + } + for (uint8_t i=0; i