Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
Astik-2002 authored Feb 27, 2024
2 parents 1161bc6 + 242f679 commit ca4c993
Show file tree
Hide file tree
Showing 70 changed files with 626 additions and 686 deletions.
1 change: 1 addition & 0 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,7 @@ jobs:
- name: Install Prerequisites
shell: bash
run: |
sudo apt-get update
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10
update-alternatives --query python
Expand Down
6 changes: 3 additions & 3 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
53 changes: 13 additions & 40 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
74 changes: 17 additions & 57 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand All @@ -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
Expand All @@ -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
}
69 changes: 16 additions & 53 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -745,72 +745,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
}

Expand Down
33 changes: 8 additions & 25 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Loading

0 comments on commit ca4c993

Please sign in to comment.