Skip to content

refactor(FirmwarePlugin): Overhaul parameter metadata parsing#14203

Open
HTRamsey wants to merge 1 commit intomavlink:masterfrom
HTRamsey:feature/firmware-updates
Open

refactor(FirmwarePlugin): Overhaul parameter metadata parsing#14203
HTRamsey wants to merge 1 commit intomavlink:masterfrom
HTRamsey:feature/firmware-updates

Conversation

@HTRamsey
Copy link
Copy Markdown
Collaborator

Summary

  • Extract ParameterMetaData abstract base class with shared XML/JSON dispatch, helpers, and load guard
  • APM: Replace XML parser with JSON parser reading apm.pdef.json from ArduPilot/ParameterRepository — eliminates 450+ lines of XML state machine code
  • PX4: Refactor XML parser — extract _parseParameterField, fix first-param-skipped bug, use QStringView, categorized logging, remove dead code
  • Move PX4 cache logic from CompInfoParam to PX4FirmwarePlugin via _cachedParameterMetaDataFile/_cacheParameterMetaDataFile virtuals
  • Eliminate two FirmwarePlugin virtual override chains (_getMetaDataForFact, _getParameterMetaDataVersionInfo)
  • 42 unit tests (23 PX4, 19 APM) verified against bundled PX4 XML (1,836 params) and APM JSON (5,645 params)

Key changes

Area Before After
APM metadata format XML (apm.pdef.xml) JSON (apm.pdef.json)
APM parser 450-line XML state machine 50-line JSON key-value iteration
PX4 parseParameterXml 300-line monolith Clean state machine + extracted _parseParameterField
CompInfoParam 300 lines, PX4-specific cache logic 130 lines, delegates to FirmwarePlugin
First parameter bug Silently skipped (both parsers) Fixed (badMetaData init)
FirmwarePlugin virtuals _getMetaDataForFact + _getParameterMetaDataVersionInfo chains Eliminated — direct calls
Test coverage 0 tests 42 tests

Bug fix

Both PX4 and APM parsers initialized badMetaData = true, causing the first parameter's sub-elements (description, min, max, units, enums, bitmask, reboot_required) to be silently skipped. Every subsequent parameter was parsed correctly. Fixed by initializing to false.

Test plan

  • 42 unit tests pass (23 PX4, 19 APM)
  • Full-file verification: all 1,836 PX4 params and 5,645 APM params parsed with zero missing
  • Connect to PX4 vehicle — verify parameter metadata loads correctly
  • Connect to ArduPilot vehicle — verify parameter metadata loads correctly
  • Verify PX4 firmware flash caches metadata correctly
  • Verify offline editing params load for both firmware types
Copilot AI review requested due to automatic review settings March 24, 2026 11:07
@HTRamsey HTRamsey force-pushed the feature/firmware-updates branch from 46b4ff4 to b7c2609 Compare March 24, 2026 11:12
@HTRamsey HTRamsey requested a review from DonLakeFlyer March 24, 2026 11:12
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Refactors firmware parameter metadata handling by introducing a shared ParameterMetaData base and migrating ArduPilot metadata parsing to JSON, while restructuring PX4 parsing and moving PX4 metadata caching responsibilities into PX4FirmwarePlugin.

Changes:

  • Add ParameterMetaData abstract base class with common XML/JSON dispatch and shared helpers.
  • Replace APM parameter metadata parsing with JSON parsing (apm.pdef.json) and update APM resource discovery/selection to .json.
  • Refactor PX4 XML parsing and relocate PX4 parameter metadata cache selection/caching into PX4FirmwarePlugin, plus add new unit tests for both stacks.

Reviewed changes

Copilot reviewed 23 out of 23 changed files in this pull request and generated 6 comments.

Show a summary per file
File Description
test/FactSystem/PX4ParameterMetaDataTest.h Declares new PX4 parameter metadata unit tests.
test/FactSystem/PX4ParameterMetaDataTest.cc Implements PX4 parser/version/full-parse verification tests.
test/FactSystem/APMParameterMetaDataTest.h Declares new APM JSON metadata unit tests.
test/FactSystem/APMParameterMetaDataTest.cc Implements APM JSON parser/full-parse verification tests.
test/FactSystem/CMakeLists.txt Adds new test sources to the test build.
test/CMakeLists.txt Registers the new APM/PX4 metadata tests.
src/FirmwarePlugin/ParameterMetaData.h Introduces shared metadata parser base interface/helpers.
src/FirmwarePlugin/ParameterMetaData.cc Implements shared file loading + enum/bitmask/value helpers.
src/FirmwarePlugin/FirmwarePlugin.h Replaces old opaque metadata virtuals with cached-file + factory API.
src/FirmwarePlugin/FirmwarePlugin.cc Removes now-unused base virtual implementation.
src/FirmwarePlugin/CMakeLists.txt Adds new ParameterMetaData sources to build.
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h Converts PX4 metadata class to derive from ParameterMetaData.
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc Refactors PX4 XML parsing and shared conversions/logging usage.
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h Adds cache-file + cache-write + metadata factory overrides.
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc Implements PX4 cache selection and cache write logic in plugin.
src/FirmwarePlugin/APM/APMParameterMetaData.h Converts APM metadata class to derive from ParameterMetaData and switch to JSON parsing.
src/FirmwarePlugin/APM/APMParameterMetaData.cc Implements APM JSON parsing and metadata object creation/caching.
src/FirmwarePlugin/APM/APMFirmwarePlugin.h Removes obsolete opaque-metadata override chain; adds factory override.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc Updates internal metadata file selection to .json and adds factory.
src/FirmwarePlugin/APM/CMakeLists.txt Switches resource discovery/aliasing from apm.pdef.xml to apm.pdef.json.
src/Vehicle/ComponentInformation/CompInfoParam.h Switches to ParameterMetaData pointer and simplifies API.
src/Vehicle/ComponentInformation/CompInfoParam.cc Uses new FirmwarePlugin factory + cached-file path; keeps JSON override parsing.
src/Vehicle/VehicleSetup/FirmwareImage.cc Routes PX4 metadata caching through FirmwarePlugin instead of CompInfoParam.
Comment on lines +10 to 16
class PX4ParameterMetaData : public ParameterMetaData
{
Q_OBJECT

public:
PX4ParameterMetaData(QObject* parent = nullptr);
explicit PX4ParameterMetaData(QObject *parent = nullptr);

void loadParameterFactMetaDataFile (const QString& metaDataFile);
FactMetaData* getMetaDataForFact (const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type);
FactMetaData *getMetaDataForFact(const QString &name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type) override;

Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

PX4ParameterMetaData no longer has a Q_OBJECT (or Q_DECLARE_TR_FUNCTIONS) macro, but the implementation still calls tr("Enabled")/tr("Disabled"). This changes the translation context away from PX4ParameterMetaData, and existing translations (see translations/qgc.ts context PX4ParameterMetaData) will stop matching. Restore Q_OBJECT/Q_DECLARE_TR_FUNCTIONS(PX4ParameterMetaData) or switch to an explicit translation context for these strings.

Copilot uses AI. Check for mistakes.
Comment on lines +402 to +406
int withDesc = 0;
int withMinMax = 0;
int withEnum = 0;
int withBitmask = 0;
int withReboot = 0;
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In _verifyFullPX4Parse, withMinMax, withEnum, withBitmask, and withReboot are incremented but never used. With -Werror enabled, this will fail the build due to unused-but-set warnings. Either remove these counters or add assertions that use them (similar to the withDesc sanity check).

Copilot uses AI. Check for mistakes.
return;
}

const QVariant rawValue = QVariant::fromValue(static_cast<qint64>(1ull << bitIndex));
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

1ull << bitIndex is undefined behavior if bitIndex >= 64. Since bit indices come from metadata files, add a range check (and log/skip invalid entries) before shifting to avoid UB on malformed or unexpected input.

Suggested change
const QVariant rawValue = QVariant::fromValue(static_cast<qint64>(1ull << bitIndex));
if (bitIndex >= 64) {
qCDebug(ParameterMetaDataLog) << "Bitmask index out of range for" << metaData->name() << "bit:" << bitIndex;
continue;
}
const quint64 bitValue = 1ull << bitIndex;
const QVariant rawValue = QVariant::fromValue(static_cast<qint64>(bitValue));
Copilot uses AI. Check for mistakes.
Comment on lines +68 to +105
auto *raw = new APMFactMetaDataRaw;
raw->name = name;
raw->group = group;
raw->shortDescription = fields.value(u"DisplayName").toString();
raw->longDescription = fields.value(u"Description").toString();
raw->units = fields.value(u"Units").toString();
raw->incrementSize = fields.value(u"Increment").toString();

const QString user = fields.value(u"User").toString();
if (!user.isEmpty()) {
raw->category = user;
}

bool badMetaData = true;
APMFactMetaDataRaw *rawMetaData = nullptr;
QString currentCategory;

QStack<int> xmlState;
xmlState.push(XmlState::None);

QMap<QString,QStringList> groupMembers; //used to remove groups with single item

while (!xml.atEnd()) {
if (xml.isStartElement()) {
const QString elementName = xml.name().toString();

if (elementName.isEmpty()) {
// skip empty elements
} else if (elementName == "paramfile") {
if (xmlState.top() != XmlState::None) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, paramfile matched";
}
xmlState.push(XmlState::ParamFileFound);
// we don't really do anything with this element
} else if (elementName == "vehicles") {
if (xmlState.top() != XmlState::ParamFileFound) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, vehicles matched";
return;
}
xmlState.push(XmlState::FoundVehicles);
} else if (elementName == "libraries") {
if (xmlState.top() != XmlState::ParamFileFound) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, libraries matched";
return;
}
currentCategory = "libraries";
xmlState.push(XmlState::FoundLibraries);
} else if (elementName == "parameters") {
if (xmlState.top() != XmlState::FoundVehicles && xmlState.top() != XmlState::FoundLibraries) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameters matched"
<< "but we don't have proper vehicle or libraries yet";
return;
}

if (xml.attributes().hasAttribute("name")) {
// we will handle metadata only for specific MAV_TYPEs and libraries
const QString nameValue = xml.attributes().value("name").toString();
static const QRegularExpression parameterCategories = QRegularExpression("ArduCopter|ArduPlane|APMrover2|Rover|ArduSub|AntennaTracker");
if (nameValue.contains(parameterCategories)) {
xmlState.push(XmlState::FoundParameters);
currentCategory = nameValue;
} else if(xmlState.top() == XmlState::FoundLibraries) {
// we handle all libraries section under the same category libraries
// so not setting currentCategory
xmlState.push(XmlState::FoundParameters);
} else {
qCDebug(APMParameterMetaDataVerboseLog) << "not interested in this block of parameters, skipping:" << nameValue;
if (_skipXMLBlock(xml, "parameters")) {
qCWarning(APMParameterMetaDataLog) << "something wrong with the xml, skip of the xml failed";
return;
}
(void) xml.readNext();
continue;
}
}
} else if (elementName == "param") {
if (xmlState.top() != XmlState::FoundParameters) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, element param matched"
<< "while we are not yet in parameters";
return;
}
xmlState.push(XmlState::FoundParameter);

if (!xml.attributes().hasAttribute("name")) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameter attribute name missing";
return;
}

QString name = xml.attributes().value("name").toString();
if (name.contains(':')) {
name = name.split(':').last();
}
const QString group = _groupFromParameterName(name);

const QString category = xml.attributes().value("user").toString();

const QString shortDescription = xml.attributes().value("humanName").toString();
const QString longDescription = xml.attributes().value("documentation").toString();

qCDebug(APMParameterMetaDataVerboseLog) << "Found parameter name:" << name
<< "short Desc:" << shortDescription
<< "longDescription:" << longDescription
<< "category:" << category
<< "group:" << group;

Q_ASSERT(!rawMetaData);
if (_vehicleTypeToParametersMap[currentCategory].contains(name)) {
qCDebug(APMParameterMetaDataLog) << "Duplicate parameter found:" << name;
rawMetaData = _vehicleTypeToParametersMap[currentCategory][name];
} else {
rawMetaData = new APMFactMetaDataRaw(this);
_vehicleTypeToParametersMap[currentCategory][name] = rawMetaData;
groupMembers[group] << name;
}
qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name;
rawMetaData->name = name;
if (!category.isEmpty()) {
rawMetaData->category = category;
}
rawMetaData->group = group;
rawMetaData->shortDescription = shortDescription;
rawMetaData->longDescription = longDescription;
} else {
// We should be getting meta data now
if (xmlState.top() != XmlState::FoundParameter) {
qCWarning(APMParameterMetaDataLog) << "Badly formed XML, while reading parameter fields wrong state";
return;
}
if (!badMetaData) {
if (!_parseParameterAttributes(xml, rawMetaData)) {
qCDebug(APMParameterMetaDataLog) << "Badly formed XML, failed to read parameter attributes";
return;
}
continue;
}
if (fields.contains(u"ReadOnly")) {
raw->readOnly = true;
}
} else if (xml.isEndElement()) {
const QString elementName = xml.name().toString();

if ((elementName == "param") && (xmlState.top() == XmlState::FoundParameter)) {
// Done loading this parameter
// Reset for next parameter
qCDebug(APMParameterMetaDataVerboseLog) << "done loading parameter";
rawMetaData = nullptr;
badMetaData = false;
xmlState.pop();
} else if (elementName == "parameters") {
qCDebug(APMParameterMetaDataVerboseLog) << "end of parameters for category: " << currentCategory;
_correctGroupMemberships(_vehicleTypeToParametersMap[currentCategory], groupMembers);
groupMembers.clear();
xmlState.pop();
} else if (elementName == "vehicles") {
qCDebug(APMParameterMetaDataVerboseLog) << "vehicles end here, libraries will follow";
xmlState.pop();
if (fields.contains(u"RebootRequired")) {
raw->rebootRequired = textToBool(fields.value(u"RebootRequired").toString());
}
}
(void) xml.readNext();
}
}

void APMParameterMetaData::_correctGroupMemberships(ParameterNametoFactMetaDataMap &parameterToFactMetaDataMap, QMap<QString,QStringList> &groupMembers)
{
for (const QString &groupName : groupMembers.keys()) {
if (groupMembers[groupName].count() == 1) {
for (const QString &parameter : groupMembers.value(groupName)) {
parameterToFactMetaDataMap[parameter]->group = FactMetaData::defaultGroup();
const QJsonObject range = fields.value(u"Range").toObject();
if (!range.isEmpty()) {
raw->min = range.value(u"low").toString();
raw->max = range.value(u"high").toString();
}

const QJsonObject values = fields.value(u"Values").toObject();
for (auto valIt = values.constBegin(); valIt != values.constEnd(); ++valIt) {
raw->values << qMakePair(valIt.key(), valIt->toString());
}

const QJsonObject bitmask = fields.value(u"Bitmask").toObject();
for (auto bitIt = bitmask.constBegin(); bitIt != bitmask.constEnd(); ++bitIt) {
raw->bitmask << qMakePair(bitIt.key(), bitIt->toString());
}

_parameterMap[name] = raw;
groupMembers[group] << name;
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_parameterMap[name] = raw; overwrites any existing entry without deleting it. Since duplicate parameter names can occur (and the tests mention duplicates), this leaks the previously allocated APMFactMetaDataRaw and discards any cached metadata associated with it. Handle duplicates explicitly (delete/replace, or merge/reuse the existing struct).

Copilot uses AI. Check for mistakes.
@github-actions
Copy link
Copy Markdown
Contributor

github-actions bot commented Mar 24, 2026

Build Results

Platform Status

Platform Status Details
Linux Failed View
Windows Passed View
MacOS Passed View
Android Passed View

Some builds failed.

Pre-commit

Check Status Details
pre-commit Failed (non-blocking) View

Pre-commit hooks: 4 passed, 32 failed, 7 skipped.

Artifact Sizes

Artifact Size
QGroundControl 329.50 MB
QGroundControl 319.72 MB
QGroundControl-installer-AMD64 150.75 MB
QGroundControl-installer-AMD64-ARM64 76.99 MB
QGroundControl-installer-ARM64 77.95 MB
QGroundControl-mac 184.05 MB
QGroundControl-windows 184.07 MB
No baseline available for comparison---
Updated: 2026-03-25 02:49:35 UTC • Triggered by: MacOS
@HTRamsey HTRamsey force-pushed the feature/firmware-updates branch from 66c73cc to c557e7c Compare March 25, 2026 00:45
@github-actions github-actions bot added the github_actions Pull requests that update GitHub Actions code label Mar 25, 2026
@HTRamsey HTRamsey force-pushed the feature/firmware-updates branch from c557e7c to f6e3f2e Compare March 25, 2026 00:45
@HTRamsey HTRamsey force-pushed the feature/firmware-updates branch from f6e3f2e to 68a483f Compare March 25, 2026 01:51
@DonLakeFlyer
Copy link
Copy Markdown
Collaborator

  • Move PX4 cache logic from CompInfoParam to PX4FirmwarePlugin via _cachedParameterMetaDataFile/_cacheParameterMetaDataFile virtuals

This seems wrong. The caching system for parameter metadata from the component information protocol is a generic mavlink thing. Just because ArduPilot doesn't support it yet doesn't make it firmware specific.

Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Copilot reviewed 25 out of 27 changed files in this pull request and generated 7 comments.

continue;
}
if (fields.contains(u"ReadOnly")) {
raw->readOnly = true;
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ReadOnly is treated as true whenever the key exists, even if the JSON value is "False"/"0". Parse the value (similar to RebootRequired) using textToBool(fields.value(u"ReadOnly").toString()) (or handle boolean-typed JSON) so read-only semantics match the metadata.

Suggested change
raw->readOnly = true;
const QJsonValue readOnlyValue = fields.value(u"ReadOnly");
if (readOnlyValue.isBool()) {
raw->readOnly = readOnlyValue.toBool();
} else {
raw->readOnly = textToBool(readOnlyValue.toString());
}
Copilot uses AI. Check for mistakes.
Comment on lines +105 to +109
const int version = doc.object().value(u"version").toInt(-1);
if (version < 0) {
return {};
}
}

void PX4ParameterMetaData::_outputFileWarning(const QString& metaDataFile, const QString& error1, const QString& error2)
{
qWarning() << QStringLiteral("Internal Error: Parameter meta data file '%1'. %2. error: %3").arg(metaDataFile).arg(error1).arg(error2);
return QVersionNumber(version, 0);
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

getParameterMetaDataVersionInfo currently returns the JSON schema version (commonly 1) and hard-codes minor to 0. This breaks PX4 cache selection logic: cache and internal files will almost always compare equal, so cached metadata won’t be preferred even when it’s newer. Prefer extracting the parameter set version fields (e.g. parameter_version_major/parameter_version_minor if present in the PX4 JSON) and return them as (major, minor); fall back to schema version only if the parameter-version fields are absent.

Copilot uses AI. Check for mistakes.
Comment on lines +10 to +15
void ParameterMetaData::loadParameterFactMetaDataFile(const QString &metaDataFile)
{
if (_parameterMetaDataLoaded) {
return;
}
_parameterMetaDataLoaded = true;
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_parameterMetaDataLoaded is set before verifying the file exists/opens/parses successfully. If the first attempt fails (missing file, parse error), subsequent attempts to load a valid file will be ignored for the lifetime of the object. Consider only setting _parameterMetaDataLoaded = true after a successful parse, or tracking a separate “attempted load” state while still allowing retry on failure.

Copilot uses AI. Check for mistakes.
Comment on lines +335 to +342
void PX4FirmwarePlugin::_cacheParameterMetaDataFile(const QString &metaDataFile)
{
const QVersionNumber newVersion = PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile);
int majorVersion = newVersion.majorVersion();
if (majorVersion != 1) {
majorVersion = 1;
qgcApp()->showAppMessage(tr("Internal Error: Parameter MetaData major must be 1"));
}
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Caching proceeds even when newVersion is null/invalid, and the copy() result is ignored. This can poison the cache (or silently fail) if the extracted metadata is malformed or the filesystem operation fails. Recommend: (1) early-return if newVersion.isNull() (or parsing failed), (2) check QFile::copy/QFile::remove return values and log failures, and (3) ensure the cache directory exists (and consider an atomic replace strategy).

Copilot uses AI. Check for mistakes.
Comment on lines +360 to 366
if (cacheNewFile) {
QSettings settings;
const QDir cacheDir = QFileInfo(settings.fileName()).dir();
QFile cacheFile(cacheDir.filePath(QStringLiteral("%1.%2.%3.json").arg(kCachedMetaDataFilePrefix).arg(MAV_AUTOPILOT_PX4).arg(majorVersion)));
QFile newFile(metaDataFile);
newFile.copy(cacheFile.fileName());
}
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Caching proceeds even when newVersion is null/invalid, and the copy() result is ignored. This can poison the cache (or silently fail) if the extracted metadata is malformed or the filesystem operation fails. Recommend: (1) early-return if newVersion.isNull() (or parsing failed), (2) check QFile::copy/QFile::remove return values and log failures, and (3) ensure the cache directory exists (and consider an atomic replace strategy).

Copilot uses AI. Check for mistakes.
Comment on lines +97 to +101
const QVariant rawValue = QVariant::fromValue(static_cast<qint64>(1ull << bitIndex));
QVariant bitmaskValue;
QString errorString;
if (metaData->convertAndValidateRaw(rawValue, false, bitmaskValue, errorString)) {
bitmaskValues << bitmaskValue;
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shifting into 1ull << bitIndex and then casting to qint64 is incorrect for bitIndex == 63 (overflow/sign) and can also distort values intended for unsigned parameter types. Use an unsigned integral variant (e.g. quint64) or build a QVariant in a type that matches the FactMetaData value type to avoid incorrect bitmask values at high indices.

Copilot uses AI. Check for mistakes.

// Cache this file with the system
CompInfoParam::_cachePX4MetaDataFile(parameterFilename);
FirmwarePlugin *fwPlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
Copy link

Copilot AI Mar 27, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Using MAV_TYPE_QUADROTOR to select a firmware plugin while flashing is unnecessarily specific and may pick a different plugin than intended if selection ever varies by vehicle type. Prefer MAV_TYPE_GENERIC (or derive the type from the image/target when available) since the goal here is firmware-type-specific metadata caching, not airframe-specific behavior.

Suggested change
FirmwarePlugin *fwPlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
FirmwarePlugin *fwPlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_GENERIC);
Copilot uses AI. Check for mistakes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

CMake github_actions Pull requests that update GitHub Actions code size/XL Tests

3 participants