mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
ArduCopter: convert EFI cvonversion to g2_conversion entry
This commit is contained in:
parent
620723767d
commit
1e2fdb0ca1
@ -1357,55 +1357,28 @@ void Copter::load_parameters(void)
|
||||
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 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
|
||||
#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);
|
||||
}
|
||||
{ &stats, stats.var_info, 12, 4044 },
|
||||
#endif
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6
|
||||
{ &scripting, scripting.var_info, 30, 94 },
|
||||
#endif
|
||||
#if AP_GRIPPER_ENABLED
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
|
||||
{ &gripper, gripper.var_info, 13, 4045},
|
||||
#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);
|
||||
#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;
|
||||
}
|
||||
|
||||
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);
|
||||
}
|
||||
#endif
|
||||
|
||||
// setup AP_Param frame type flags
|
||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user