diff --git a/qgcresources.qrc b/qgcresources.qrc
index 67be220..d7fbf23 100644
--- a/qgcresources.qrc
+++ b/qgcresources.qrc
@@ -231,13 +231,15 @@
src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
- src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml
- src/FirmwarePlugin/APM/apm.pdef.xml
+ src/FirmwarePlugin/APM/APMParameterFactMetaData.xml
+
+
+ src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
resources/opengl/buglist.json
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index c4bc239..0213803 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -606,7 +606,6 @@ HEADERS+= \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \
- src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
src/Vehicle/MultiVehicleManager.h \
@@ -661,8 +660,8 @@ SOURCES += \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \
+ src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
- src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
src/Vehicle/MultiVehicleManager.cc \
diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
index d334a10..e45624a 100644
--- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
+++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
@@ -25,7 +25,6 @@
/// @author Don Gagne
#include "GenericAutoPilotPlugin.h"
-#include "FirmwarePlugin/Generic/GenericFirmwarePlugin.h" // FIXME: Hack
GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent)
diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
index f962149..3e8b0b1 100644
--- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
+++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
@@ -1,6 +1,7 @@
1
+ 1
Emmanuel Roussel
@@ -230,6 +231,13 @@
Blankered
Quadrotor x
+
+ Mark Whitehorn <kd0aij@gmail.com>
+ Quadrotor x
+
+
+
+
diff --git a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc
index 4a964da..44c83f9 100644
--- a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc
+++ b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc
@@ -134,6 +134,10 @@ void PX4AirframeLoader::loadAirframeMetaData(void)
return;
}
+ } else if (elementName == "airframe_version_major") {
+ // Just skip over for now
+ } else if (elementName == "airframe_version_minor") {
+ // Just skip over for now
} else if (elementName == "airframe_group") {
if (xmlState != XmlStateFoundVersion) {
diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc
index c07f40e..5ac6e52 100644
--- a/src/FactSystem/ParameterLoader.cc
+++ b/src/FactSystem/ParameterLoader.cc
@@ -40,14 +40,14 @@ typedef QPair ParamTypeVal;
typedef QPair NamedParam;
typedef QMap MapID2NamedParam;
-QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
Fact ParameterLoader::_defaultFact;
-ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent)
- : QObject(parent)
- , _autopilot(autopilot)
+const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParamaterFactMetaData";
+
+ParameterLoader::ParameterLoader(Vehicle* vehicle)
+ : QObject(vehicle)
, _vehicle(vehicle)
, _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
, _dedicatedLink(_vehicle->priorityLink())
@@ -55,9 +55,10 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
, _initialLoadComplete(false)
, _saveRequired(false)
, _defaultComponentId(FactSystem::defaultComponentId)
+ , _parameterSetMajorVersion(-1)
+ , _parameterMetaData(NULL)
, _totalParamCount(0)
{
- Q_ASSERT(_autopilot);
Q_ASSERT(_vehicle);
Q_ASSERT(_mavlink);
@@ -74,6 +75,9 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate);
+ _versionParam = vehicle->firmwarePlugin()->getVersionParam();
+ _defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
+
// Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
refreshAllParameters();
@@ -81,14 +85,12 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q
ParameterLoader::~ParameterLoader()
{
-
+ delete _parameterMetaData;
}
/// Called whenever a parameter is updated or first seen.
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
{
- bool setMetaData = false;
-
// Is this for our uas?
if (uasId != _vehicle->id()) {
return;
@@ -198,14 +200,16 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
emit parameterListProgress((float)(_totalParamCount - waitingParamCount) / (float)_totalParamCount);
}
- // Attempt to determine default component id
- if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
- _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam();
- }
+ // Determine default component id
if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
_defaultComponentId = componentId;
}
+ // Get parameter set version
+ if (!_versionParam.isEmpty() && _versionParam == parameterName) {
+ _parameterSetMajorVersion = value.toInt();
+ }
+
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
qCDebug(ParameterLoaderLog) << "Adding new fact";
@@ -242,7 +246,6 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
}
Fact* fact = new Fact(componentId, parameterName, factType, this);
- setMetaData = true;
_mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
@@ -258,10 +261,6 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
Q_ASSERT(fact);
fact->_containerSetRawValue(value);
- if (setMetaData) {
- _vehicle->firmwarePlugin()->addMetaDataToFact(fact, _vehicle->vehicleType());
- }
-
if (waitingParamCount == 0) {
// Now that we know vehicle is up to date persist
_saveToEEPROM();
@@ -487,7 +486,7 @@ void ParameterLoader::_waitingParamTimeout(void)
foreach(const QString ¶mName, _waitingWriteParamNameMap[componentId].keys()) {
paramsRequested = true;
_waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count
- _writeParameterRaw(componentId, paramName, _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
+ _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
@@ -539,7 +538,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa
mavlink_param_set_t p;
mavlink_param_union_t union_value;
- FactMetaData::ValueType_t factType = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
+ FactMetaData::ValueType_t factType = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->type();
p.param_type = _factTypeToMavType(factType);
switch (factType) {
@@ -701,7 +700,7 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QString valStr = wpParams.at(3);
uint mavType = wpParams.at(4).toUInt();
- if (!_autopilot->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
+ if (!_vehicle->autopilotPlugin()->factExists(FactSystem::ParameterProvider, componentId, paramName)) {
QString error;
error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
errors += error;
@@ -709,7 +708,7 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
continue;
}
- Fact* fact = _autopilot->getFact(FactSystem::ParameterProvider, componentId, paramName);
+ Fact* fact = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName);
if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) {
QString error;
error = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType));
@@ -810,6 +809,33 @@ void ParameterLoader::_restartWaitingParamTimer(void)
_waitingParamTimeoutTimer.start();
}
+/// Adds meta data to all params after initial load completes
+void ParameterLoader::_addMetaDataToAll(void)
+{
+ if (_defaultComponentId == FactSystem::defaultComponentId) {
+ // We don't know what the default component is so we can't support meta data
+ return;
+ }
+
+ if (_parameterMetaData) {
+ // This should only be called once
+ qWarning() << "Internal Error: ParameterLoader::_addMetaDataToAll with _parameterMetaData non NULL";
+ return;
+ }
+
+ // Load best parameter meta data set
+ int majorVersion, minorVersion;
+ QString metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
+ _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
+ qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
+
+ // Loop over all parameters in default component adding meta data
+ QVariantMap& factMap = _mapParameterName2Variant[_defaultComponentId];
+ foreach (const QString& key, factMap.keys()) {
+ _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value(), _vehicle->vehicleType());
+ }
+}
+
void ParameterLoader::_checkInitialLoadComplete(void)
{
// Already processed?
@@ -824,7 +850,6 @@ void ParameterLoader::_checkInitialLoadComplete(void)
}
}
-
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete = true;
@@ -871,6 +896,9 @@ void ParameterLoader::_checkInitialLoadComplete(void)
}
}
+ // We can now add meta data since we should know parameter set version
+ _addMetaDataToAll();
+
// Warn of parameter load failure
if (initialLoadFailures) {
@@ -895,3 +923,141 @@ void ParameterLoader::_initialRequestTimeout(void)
refreshAllParameters();
_initialRequestTimeoutTimer.start();
}
+
+QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
+{
+ bool cacheHit = false;
+ FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
+
+ // Cached files are stored in settings location
+ QSettings settings;
+ QDir cacheDir = QFileInfo(settings.fileName()).dir();
+
+ // First look for a direct cache hit
+ int cacheMinorVersion, cacheMajorVersion;
+ QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion)));
+ if (cacheFile.exists()) {
+ plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion);
+ if (wantedMajorVersion != cacheMajorVersion) {
+ qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
+ } else {
+ qCDebug(ParameterLoaderLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
+ cacheHit = true;
+ }
+ }
+
+ if (!cacheHit) {
+ // No direct hit, look for lower param set version
+ QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType);
+ QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name);
+
+ // Find the highest major version number which is below the vehicles major version number
+ int cacheHitIndex = -1;
+ cacheMajorVersion = -1;
+ QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType));
+ for (int i=0; i< cacheHits.count(); i++) {
+ if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) {
+ int majorVersion = regExp.capturedTexts()[0].toInt();
+ if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) {
+ cacheMajorVersion = majorVersion;
+ cacheHitIndex = i;
+ }
+ }
+ }
+
+ if (cacheHitIndex != -1) {
+ // We have a cache hit on a lower major version, read minor version as well
+ int majorVersion;
+ cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex]));
+ plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion);
+ if (majorVersion != cacheMajorVersion) {
+ qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
+ cacheHit = false;
+ } else {
+ qCDebug(ParameterLoaderLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
+ cacheHit = true;
+ }
+ }
+ }
+
+ int internalMinorVersion, internalMajorVersion;
+ QString internalMetaDataFile = plugin->internalParameterMetaDataFile();
+ plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
+ qCDebug(ParameterLoaderLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
+ if (cacheHit) {
+ // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
+ if (internalMajorVersion == wantedMajorVersion) {
+ if (cacheMajorVersion == wantedMajorVersion) {
+ // Both internal and cache are direct hit on major version, Use higher minor version number
+ cacheHit = cacheMinorVersion > internalMinorVersion;
+ } else {
+ // Direct internal hit, but not direct hit in cache, use internal
+ cacheHit = false;
+ }
+ } else {
+ if (cacheMajorVersion == wantedMajorVersion) {
+ // Direct hit on cache, no direct hit on internal, use cache
+ cacheHit = true;
+ } else {
+ // No direct hit anywhere, use internal
+ cacheHit = false;
+ }
+ }
+ }
+
+ QString metaDataFile;
+ if (cacheHit && !qgcApp()->runningUnitTests()) {
+ majorVersion = cacheMajorVersion;
+ minorVersion = cacheMinorVersion;
+ metaDataFile = cacheFile.fileName();
+ } else {
+ majorVersion = internalMajorVersion;
+ minorVersion = internalMinorVersion;
+ metaDataFile = internalMetaDataFile;
+ }
+ qCDebug(ParameterLoaderLog) << "ParameterLoader::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
+
+ return metaDataFile;
+}
+
+void ParameterLoader::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
+{
+ FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
+
+ int newMajorVersion, newMinorVersion;
+ plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
+ qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
+
+ // Find the cache hit closest to this new file
+ int cacheMajorVersion, cacheMinorVersion;
+ QString cacheHit = ParameterLoader::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
+ qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
+
+ bool cacheNewFile = false;
+ if (cacheHit.isEmpty()) {
+ // No cache hits, store the new file
+ cacheNewFile = true;
+ } else if (cacheMajorVersion == newMajorVersion) {
+ // Direct hit on major version in cache:
+ // Cache new file if newer minor version
+ // Also delete older cache file
+ if (newMinorVersion > cacheMinorVersion) {
+ cacheNewFile = true;
+ QFile::remove(cacheHit);
+ }
+ } else {
+ // Indirect hit in cache, store new file
+ cacheNewFile = true;
+ }
+
+ if (cacheNewFile) {
+ // Cached files are stored in settings location. Copy from current file to cache naming.
+
+ QSettings settings;
+ QDir cacheDir = QFileInfo(settings.fileName()).dir();
+ QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion)));
+ qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile caching file:" << cacheFile.fileName();
+ QFile newFile(metaDataFile);
+ newFile.copy(cacheFile.fileName());
+ }
+}
diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h
index 4c17cd0..9e185a4 100644
--- a/src/FactSystem/ParameterLoader.h
+++ b/src/FactSystem/ParameterLoader.h
@@ -40,7 +40,6 @@
/// @file
/// @author Don Gagne
-Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog)
/// Connects to Parameter Manager to load/update Facts
@@ -50,7 +49,7 @@ class ParameterLoader : public QObject
public:
/// @param uas Uas which this set of facts is associated with
- ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
+ ParameterLoader(Vehicle* vehicle);
~ParameterLoader();
@@ -91,6 +90,19 @@ public:
QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream);
+
+ /// Returns the version number for the parameter set, -1 if not known
+ int parameterSetVersion(void) { return _parameterSetMajorVersion; }
+
+ /// Returns the newest available parameter meta data file (from cache or internal) for the specified information.
+ /// @param wantedMajorVersion Major version you are looking for
+ /// @param[out] majorVersion Major version for found meta data
+ /// @param[out] minorVersion Minor version for found meta data
+ /// @return Meta data file name of best match, emptyString is none found
+ static QString parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion);
+
+ /// If this file is newer than anything in the cache, cache it as the latest version
+ static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
signals:
/// Signalled when the full set of facts are ready
@@ -103,7 +115,6 @@ signals:
void restartWaitingParamTimer(void);
protected:
- AutoPilotPlugin* _autopilot;
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
@@ -123,6 +134,7 @@ private:
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int uasId, int componentId);
void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
+ void _addMetaDataToAll(void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
@@ -134,18 +146,22 @@ private:
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap _mapParameterName2Variant;
+
QMap > _mapParameterId2Name;
/// First mapping is by component id
/// Second mapping is group name, to Fact
QMap > _mapGroup2ParameterName;
- bool _parametersReady; ///< true: full set of parameters correctly loaded
- bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
- bool _saveRequired; ///< true: _saveToEEPROM should be called
- int _defaultComponentId;
- QString _defaultComponentIdParam;
-
+ bool _parametersReady; ///< true: full set of parameters correctly loaded
+ bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
+ bool _saveRequired; ///< true: _saveToEEPROM should be called
+ int _defaultComponentId;
+ QString _defaultComponentIdParam; ///< Parameter which identifies default component
+ QString _versionParam; ///< Parameter which contains parameter set version
+ int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
+ QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
+
static const int _maxInitialLoadRetry = 10; ///< Maximum a retries on initial index based load
QMap _paramCountMap; ///< Key: Component id, Value: count of parameters in this component
@@ -162,6 +178,8 @@ private:
QMutex _dataMutex;
static Fact _defaultFact; ///< Used to return default fact, when parameter not found
+
+ static const char* _cachedMetaDataFilePrefix;
};
#endif
diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
index 6ebf05d..812993b 100644
--- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
@@ -25,7 +25,6 @@
/// @author Don Gagne
#include "APMFirmwarePlugin.h"
-#include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h"
#include "QGCApplication.h"
@@ -473,11 +472,16 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return true;
}
-void APMFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
+void APMFirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
{
- _parameterMetaData.addMetaDataToFact(fact, vehicleType);
-}
+ APMParameterMetaData* apmMetaData = qobject_cast(parameterMetaData);
+ if (apmMetaData) {
+ apmMetaData->addMetaDataToFact(fact, vehicleType);
+ } else {
+ qWarning() << "Internal error: pointer passed to APMFirmwarePlugin::addMetaDataToFact not APMParameterMetaData";
+ }
+}
QList APMFirmwarePlugin::supportedMissionCommands(void)
{
@@ -508,3 +512,11 @@ void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt
fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
}
+
+QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
+{
+ Q_UNUSED(metaDataFile);
+
+ APMParameterMetaData* metaData = new APMParameterMetaData;
+ return metaData;
+}
diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h
index 58edaa1..7a7e7bc 100644
--- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h
@@ -80,19 +80,25 @@ class APMFirmwarePlugin : public FirmwarePlugin
public:
// Overrides from FirmwarePlugin
- virtual bool isCapable(FirmwareCapabilities capabilities);
- virtual QList componentsForVehicle(AutoPilotPlugin* vehicle);
- virtual QStringList flightModes(void);
- virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
- virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
- virtual int manualControlReservedButtonCount(void);
- virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
- virtual void initializeVehicle(Vehicle* vehicle);
- virtual bool sendHomePositionToVehicle(void);
- virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
- virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
- virtual QList supportedMissionCommands(void);
- void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
+
+ QList componentsForVehicle(AutoPilotPlugin* vehicle) final;
+ QList supportedMissionCommands(void) final;
+
+ bool isCapable(FirmwareCapabilities capabilities) final;
+ QStringList flightModes(void) final;
+ QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
+ bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
+ int manualControlReservedButtonCount(void) final;
+ void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
+ void initializeVehicle(Vehicle* vehicle) final;
+ bool sendHomePositionToVehicle(void) final;
+ void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
+ QString getDefaultComponentIdParam(void) const final { return QString("SYSID_SW_TYPE"); }
+ void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
+ QString getVersionParam(void) final { return QStringLiteral("SYSID_SW_MREV"); }
+ QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/APM/APMParameterFactMetaData.xml"); }
+ void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
+ QObject* loadParameterMetaData (const QString& metaDataFile);
protected:
/// All access to singleton is through stack specific implementation
@@ -109,7 +115,6 @@ private:
APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded;
QList _supportedModes;
- APMParameterMetaData _parameterMetaData;
};
#endif
diff --git a/src/FirmwarePlugin/APM/apm.pdef.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.xml
similarity index 100%
rename from src/FirmwarePlugin/APM/apm.pdef.xml
rename to src/FirmwarePlugin/APM/APMParameterFactMetaData.xml
diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc
index 2ad3c75..ce391fb 100644
--- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc
+++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc
@@ -21,9 +21,6 @@
======================================================================*/
-/// @file
-/// @author Don Gagne
-
#include "APMParameterMetaData.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
@@ -34,15 +31,13 @@
#include
#include
-QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
-QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
-
-bool APMParameterMetaData::_parameterMetaDataLoaded = false;
-QMap APMParameterMetaData::_vehicleTypeToParametersMap;
+QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
+QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
-APMParameterMetaData::APMParameterMetaData(QObject* parent) :
- QObject(parent)
+APMParameterMetaData::APMParameterMetaData(void)
+ : _parameterMetaDataLoaded(false)
{
+ // APM meta data is not yet versioned
_loadParameterFactMetaData();
}
@@ -146,7 +141,7 @@ void APMParameterMetaData::_loadParameterFactMetaData()
// Fixme:: always picking up the bundled xml, we would like to update it from web
// just not sure right now as the xml is in bad shape.
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
- parameterFilename = ":/FirmwarePlugin/APM/apm.pdef.xml";
+ parameterFilename = ":/FirmwarePlugin/APM/APMParameterFactMetaData.xml";
}
qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename;
@@ -428,11 +423,8 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa
return true;
}
-/// Override from FactLoad which connects the meta data to the fact
void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{
- _loadParameterFactMetaData();
-
const QString mavTypeString = mavTypeToString(vehicleType);
APMFactMetaDataRaw* rawMetaData = NULL;
@@ -591,3 +583,12 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
// FixMe:: not handling increment size as their is no place for it in FactMetaData and no ui
fact->setMetaData(metaData);
}
+
+void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
+{
+ Q_UNUSED(metaDataFile);
+
+ // Versioning not yet supported
+ majorVersion = -1;
+ minorVersion = -1;
+}
diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.h b/src/FirmwarePlugin/APM/APMParameterMetaData.h
index 66a4749..323c265 100644
--- a/src/FirmwarePlugin/APM/APMParameterMetaData.h
+++ b/src/FirmwarePlugin/APM/APMParameterMetaData.h
@@ -34,6 +34,9 @@
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
+Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
+Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
+
class APMFactMetaDataRaw
{
public:
@@ -54,11 +57,6 @@ public:
QList > bitmask;
};
-/// @file
-/// @author Don Gagne
-
-Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
-Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
/// Collection of Parameter Facts for PX4 AutoPilot
@@ -69,15 +67,11 @@ class APMParameterMetaData : public QObject
Q_OBJECT
public:
- /// @param uas Uas which this set of facts is associated with
- APMParameterMetaData(QObject* parent = NULL);
+ APMParameterMetaData(void);
- /// Override from ParameterLoader
- virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
-
- // Overrides from ParameterLoader
- static void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
- static void addMetaDataToFacts(QVariantMap &facts, MAV_TYPE vehicleType);
+ void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
+
+ static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
private:
enum {
@@ -90,18 +84,17 @@ private:
XmlStateFoundGroup,
XmlStateFoundParameter,
XmlStateDone
- };
-
+ };
- static void _loadParameterFactMetaData();
- static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
- static bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
- static bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
- static void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap& groupMembers);
- static QString mavTypeToString(MAV_TYPE vehicleTypeEnum);
+ void _loadParameterFactMetaData();
+ QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
+ bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
+ bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
+ void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap& groupMembers);
+ QString mavTypeToString(MAV_TYPE vehicleTypeEnum);
- static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
- static QMap _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map>
+ bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
+ QMap _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map>
};
#endif
diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
index d57d0a0..23c793f 100644
--- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
@@ -25,7 +25,6 @@
/// @author Don Gagne
#include "ArduCopterFirmwarePlugin.h"
-#include "Generic/GenericFirmwarePlugin.h"
APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable)
diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
index 3403262..2630bae 100644
--- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas
#include "ArduPlaneFirmwarePlugin.h"
-#include "Generic/GenericFirmwarePlugin.h"
APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
index 7fcd859..6c695eb 100644
--- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas
#include "ArduRoverFirmwarePlugin.h"
-#include "Generic/GenericFirmwarePlugin.h"
APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc
similarity index 69%
rename from src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
rename to src/FirmwarePlugin/FirmwarePlugin.cc
index a8b4cb2..2e0e38c 100644
--- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/FirmwarePlugin.cc
@@ -21,22 +21,18 @@
======================================================================*/
-/// @file
-/// @author Don Gagne
-
-#include "GenericFirmwarePlugin.h"
-#include "AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h" // FIXME: Hack
+#include "FirmwarePlugin.h"
#include
-QList GenericFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
+QList FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
Q_UNUSED(vehicle);
return QList();
}
-QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode)
+QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode)
{
QString flightMode;
@@ -72,25 +68,25 @@ QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mod
return flightMode;
}
-bool GenericFirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
+bool FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
Q_UNUSED(flightMode);
Q_UNUSED(base_mode);
Q_UNUSED(custom_mode);
- qWarning() << "GenericFirmwarePlugin::setFlightMode called on base class, not supported";
+ qWarning() << "FirmwarePlugin::setFlightMode called on base class, not supported";
return false;
}
-int GenericFirmwarePlugin::manualControlReservedButtonCount(void)
+int FirmwarePlugin::manualControlReservedButtonCount(void)
{
// We don't know whether the firmware is going to used any of these buttons.
// So reserve them all.
return -1;
}
-void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
+void FirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
Q_UNUSED(message);
@@ -98,14 +94,14 @@ void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_messa
// Generic plugin does no message adjustment
}
-void GenericFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
+void FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
// Generic Flight Stack is by definition "generic", so no extra work
}
-bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
+bool FirmwarePlugin::sendHomePositionToVehicle(void)
{
// Generic stack does not want home position sent in the first position.
// Subsequent sequence numbers must be adjusted.
@@ -113,25 +109,23 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return false;
}
-void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
-{
- Q_UNUSED(vehicleType)
-
- // Add default meta data
- FactMetaData* metaData = new FactMetaData(fact->type(), fact);
- fact->setMetaData(metaData);
-}
-
-QList GenericFirmwarePlugin::supportedMissionCommands(void)
+QList FirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
return QList();
}
-void GenericFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
+void FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{
// No overrides
commonJsonFilename.clear();
fixedWingJsonFilename.clear();
multiRotorJsonFilename.clear();
}
+
+void FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
+{
+ Q_UNUSED(metaDataFile);
+ majorVersion = -1;
+ minorVersion = -1;
+}
diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h
index 14d497c..6bdc4f8 100644
--- a/src/FirmwarePlugin/FirmwarePlugin.h
+++ b/src/FirmwarePlugin/FirmwarePlugin.h
@@ -38,12 +38,10 @@ class Vehicle;
/// This is the base class for Firmware specific plugins
///
-/// The FirmwarePlugin class is the abstract base class which represents the methods and objects
-/// which are specific to a certain Firmware flight stack. This is the only place where
-/// flight stack specific code should reside in QGroundControl. The remainder of the
-/// QGroundControl source is generic to a common mavlink implementation. The implementation
-/// in the base class supports mavlink generic firmware. Override the base clase virtuals
-/// to create you firmware specific plugin.
+/// The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack.
+/// This is the only place where flight stack specific code should reside in QGroundControl. The remainder of the
+/// QGroundControl source is generic to a common mavlink implementation. The implementation in the base class supports
+/// mavlink generic firmware. Override the base clase virtuals to create your own firmware specific plugin.
class FirmwarePlugin : public QObject
{
@@ -53,31 +51,30 @@ public:
/// Set of optional capabilites which firmware may support
typedef enum {
SetFlightModeCapability, ///< FirmwarePlugin::setFlightMode method is supported
- MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
-
+ MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
} FirmwareCapabilities;
/// @return true: Firmware supports all specified capabilites
- virtual bool isCapable(FirmwareCapabilities capabilities) = 0;
-
+ virtual bool isCapable(FirmwareCapabilities capabilities) { Q_UNUSED(capabilities); return false; }
+
/// Returns VehicleComponents for specified Vehicle
/// @param vehicle Vehicle to associate with components
/// @return List of VehicleComponents for the specified vehicle. Caller owns returned objects and must
/// free when no longer needed.
- virtual QList componentsForVehicle(AutoPilotPlugin* vehicle) = 0;
+ virtual QList componentsForVehicle(AutoPilotPlugin* vehicle);
/// Returns the list of available flight modes
- virtual QStringList flightModes(void) = 0;
+ virtual QStringList flightModes(void) { return QStringList(); }
/// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable.
/// @param base_mode Base mode from mavlink HEARTBEAT message
/// @param custom_mode Custom mode from mavlink HEARTBEAT message
- virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) = 0;
+ virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
/// Sets base_mode and custom_mode to specified flight mode.
/// @param[out] base_mode Base mode for SET_MODE mavlink message
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message
- virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) = 0;
+ virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
/// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific
/// not just this. I'm going to try to change that. If not, this will need to be removed.
@@ -85,17 +82,17 @@ public:
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
/// The remainder can be assigned to Vehicle actions.
/// @return -1: reserver all buttons, >0 number of buttons to reserve
- virtual int manualControlReservedButtonCount(void) = 0;
+ virtual int manualControlReservedButtonCount(void);
/// Called before any mavlink message is processed by Vehicle such that the firmwre plugin
/// can adjust any message characteristics. This is handy to adjust or differences in mavlink
/// spec implementations such that the base code can remain mavlink generic.
/// @param vehicle Vehicle message came from
/// @param message[in,out] Mavlink message to adjust if needed.
- virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) = 0;
+ virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
/// Called when Vehicle is first created to send any necessary mavlink messages to the firmware.
- virtual void initializeVehicle(Vehicle* vehicle) = 0;
+ virtual void initializeVehicle(Vehicle* vehicle);
/// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position.
@@ -103,22 +100,38 @@ public:
/// true: Send first mission item as home position to vehicle. When vehicle has no mission items on
/// it, it may or may not return a home position back in position 0.
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
- virtual bool sendHomePositionToVehicle(void) = 0;
+ virtual bool sendHomePositionToVehicle(void);
/// Returns the parameter that is used to identify the default component
- virtual QString getDefaultComponentIdParam(void) const = 0;
+ virtual QString getDefaultComponentIdParam(void) const { return QString(); }
+
+ /// Returns the parameter which is used to identify the version number of parameter set
+ virtual QString getVersionParam(void) { return QString(); }
+
+ /// Returns the parameter set version info pulled from inside the meta data file. -1 if not found.
+ virtual void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
+
+ /// Returns the internal resource parameter meta date file.
+ virtual QString internalParameterMetaDataFile(void) { return QString(); }
+
+ /// Loads the specified parameter meta data file.
+ /// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is reponsible to
+ /// call deleteParameterMetaData when no longer needed.
+ virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; }
/// Adds the parameter meta data to the Fact
- virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) = 0;
+ /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
+ virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; }
/// List of supported mission commands. Empty list for all commands supported.
- virtual QList supportedMissionCommands(void) = 0;
+ virtual QList supportedMissionCommands(void);
/// Returns the names for the mission command json override files. Empty string to specify no overrides.
/// @param[out] commonJsonFilename Filename for common overrides
/// @param[out] fixedWingJsonFilename Filename for fixed wing overrides
/// @param[out] multiRotorJsonFilename Filename for multi rotor overrides
- virtual void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const = 0;
+ virtual void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const;
+
};
#endif
diff --git a/src/FirmwarePlugin/FirmwarePluginManager.cc b/src/FirmwarePlugin/FirmwarePluginManager.cc
index 3cd3373..d0aa23d 100644
--- a/src/FirmwarePlugin/FirmwarePluginManager.cc
+++ b/src/FirmwarePlugin/FirmwarePluginManager.cc
@@ -25,7 +25,6 @@
/// @author Don Gagne
#include "FirmwarePluginManager.h"
-#include "Generic/GenericFirmwarePlugin.h"
#include "APM/ArduCopterFirmwarePlugin.h"
#include "APM/ArduPlaneFirmwarePlugin.h"
#include "APM/ArduRoverFirmwarePlugin.h"
@@ -91,7 +90,12 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT
}
if (!_genericFirmwarePlugin) {
- _genericFirmwarePlugin = new GenericFirmwarePlugin;
+ _genericFirmwarePlugin = new FirmwarePlugin;
}
return _genericFirmwarePlugin;
}
+
+void FirmwarePluginManager::clearSettings(void)
+{
+ // FIXME: NYI
+}
diff --git a/src/FirmwarePlugin/FirmwarePluginManager.h b/src/FirmwarePlugin/FirmwarePluginManager.h
index 6a65501..f3d18b4 100644
--- a/src/FirmwarePlugin/FirmwarePluginManager.h
+++ b/src/FirmwarePlugin/FirmwarePluginManager.h
@@ -38,7 +38,6 @@ class ArduCopterFirmwarePlugin;
class ArduPlaneFirmwarePlugin;
class ArduRoverFirmwarePlugin;
class PX4FirmwarePlugin;
-class GenericFirmwarePlugin;
/// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type.
@@ -56,11 +55,14 @@ public:
/// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT.
FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType);
+ /// Clears settings from all firmware plugins.
+ void clearSettings(void);
+
private:
ArduCopterFirmwarePlugin* _arduCopterFirmwarePlugin;
ArduPlaneFirmwarePlugin* _arduPlaneFirmwarePlugin;
ArduRoverFirmwarePlugin* _arduRoverFirmwarePlugin;
- GenericFirmwarePlugin* _genericFirmwarePlugin;
+ FirmwarePlugin* _genericFirmwarePlugin;
PX4FirmwarePlugin* _px4FirmwarePlugin;
};
diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
deleted file mode 100644
index 0a21101..0000000
--- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/*=====================================================================
-
- QGroundControl Open Source Ground Control Station
-
- (c) 2009 - 2014 QGROUNDCONTROL PROJECT
-
- This file is part of the QGROUNDCONTROL project
-
- QGROUNDCONTROL is free software: you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation, either version 3 of the License, or
- (at your option) any later version.
-
- QGROUNDCONTROL is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- GNU General Public License for more details.
-
- You should have received a copy of the GNU General Public License
- along with QGROUNDCONTROL. If not, see .
-
- ======================================================================*/
-
-/// @file
-/// @author Don Gagne
-
-#ifndef GenericFirmwarePlugin_H
-#define GenericFirmwarePlugin_H
-
-#include "FirmwarePlugin.h"
-
-class GenericFirmwarePlugin : public FirmwarePlugin
-{
- Q_OBJECT
-
-public:
- // Overrides from FirmwarePlugin
- bool isCapable(FirmwareCapabilities capabilities) final { Q_UNUSED(capabilities); return false; }
- QList componentsForVehicle(AutoPilotPlugin* vehicle) final;
- QStringList flightModes(void) final { return QStringList(); }
- QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
- bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
- int manualControlReservedButtonCount(void) final;
- void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
- void initializeVehicle(Vehicle* vehicle) final;
- bool sendHomePositionToVehicle(void) final;
- void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
- QString getDefaultComponentIdParam(void) const final { return QString(); }
- QList supportedMissionCommands(void) final;
- void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
-};
-
-#endif
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
index 14b1a6e..90aeb08 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
@@ -25,6 +25,7 @@
/// @author Don Gagne
#include "PX4FirmwarePlugin.h"
+#include "PX4ParameterMetaData.h"
#include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h" // FIXME: Hack
#include
@@ -204,9 +205,15 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return false;
}
-void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
+void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
{
- _parameterMetaData.addMetaDataToFact(fact, vehicleType);
+ PX4ParameterMetaData* px4MetaData = qobject_cast(parameterMetaData);
+
+ if (px4MetaData) {
+ px4MetaData->addMetaDataToFact(fact, vehicleType);
+ } else {
+ qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData";
+ }
}
QList PX4FirmwarePlugin::supportedMissionCommands(void)
@@ -233,3 +240,10 @@ void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt
fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
}
+
+QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
+{
+ PX4ParameterMetaData* metaData = new PX4ParameterMetaData;
+ metaData->loadParameterFactMetaDataFile(metaDataFile);
+ return metaData;
+}
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
index c796af3..4d8f9fd 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
@@ -28,6 +28,7 @@
#define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h"
+#include "ParameterLoader.h"
#include "PX4ParameterMetaData.h"
class PX4FirmwarePlugin : public FirmwarePlugin
@@ -36,22 +37,25 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public:
// Overrides from FirmwarePlugin
- bool isCapable(FirmwareCapabilities capabilities) final;
+
QList componentsForVehicle(AutoPilotPlugin* vehicle) final;
- QStringList flightModes(void) final;
- QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
- bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
- int manualControlReservedButtonCount(void) final;
- void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
- void initializeVehicle(Vehicle* vehicle) final;
- bool sendHomePositionToVehicle(void) final;
- void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) final;
- QString getDefaultComponentIdParam(void) const final { return QString("SYS_AUTOSTART"); }
QList supportedMissionCommands(void) final;
- void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
-private:
- PX4ParameterMetaData _parameterMetaData;
+ bool isCapable (FirmwareCapabilities capabilities) final;
+ QStringList flightModes (void) final;
+ QString flightMode (uint8_t base_mode, uint32_t custom_mode) final;
+ bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
+ int manualControlReservedButtonCount(void) final;
+ void adjustMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final;
+ void initializeVehicle (Vehicle* vehicle) final;
+ bool sendHomePositionToVehicle (void) final;
+ void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
+ QString getDefaultComponentIdParam (void) const final { return QString("SYS_AUTOSTART"); }
+ void missionCommandOverrides (QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
+ QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); }
+ QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
+ void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
+ QObject* loadParameterMetaData (const QString& metaDataFile);
};
#endif
diff --git a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
similarity index 99%
rename from src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
rename to src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index f6f2bbb..28225ce 100644
--- a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -1,6 +1,8 @@
3
+ 1
+ 1
Speed controller bandwidth
@@ -1267,21 +1269,21 @@ replay messages for logging
Enable or disable usage of terrain estimate during landing
0: disabled, 1: enabled
-
+
Flare, minimum pitch
Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached
0
15.0
degrees
-
+
Flare, maximum pitch
Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached
0
45.0
degrees
-
+
Landing airspeed scale factor
Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach.
1.0
@@ -2001,7 +2003,7 @@ replay messages for logging
1.0
2
-
+
Proportional gain for horizontal position error
0.0
2
@@ -2022,12 +2024,14 @@ replay messages for logging
0.0
3
-
+
Maximum horizontal velocity
Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).
0.0
+ 20.0
m/s
2
+ 1
Horizontal velocity feed forward
@@ -2109,12 +2113,13 @@ replay messages for logging
Hz
2
-
+
Maximum horizonal acceleration in velocity controlled modes
2.0
- 10.0
+ 15.0
m/s/s
2
+ 1
Minimum thrust
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
index 4fe2703..043eed2 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
+++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
@@ -35,11 +35,8 @@
QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog")
-bool PX4ParameterMetaData::_parameterMetaDataLoaded = false;
-QMap PX4ParameterMetaData::_mapParameterName2FactMetaData;
-
-PX4ParameterMetaData::PX4ParameterMetaData(QObject* parent) :
- QObject(parent)
+PX4ParameterMetaData::PX4ParameterMetaData(void)
+ : _parameterMetaDataLoaded(false)
{
}
@@ -78,46 +75,29 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
return var;
}
-QString PX4ParameterMetaData::parameterMetaDataFile(void)
+void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
{
- QSettings settings;
- QDir parameterDir = QFileInfo(settings.fileName()).dir();
- return parameterDir.filePath("PX4ParameterFactMetaData.xml");
-}
+ qCDebug(ParameterLoaderLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile;
-/// Load Parameter Fact meta data
-///
-/// The meta data comes from firmware parameters.xml file.
-void PX4ParameterMetaData::_loadParameterFactMetaData(void)
-{
if (_parameterMetaDataLoaded) {
+ qWarning() << "Internal error: parameter meta data loaded more than once";
return;
}
_parameterMetaDataLoaded = true;
-
- qCDebug(PX4ParameterMetaDataLog) << "Loading PX4 parameter fact meta data";
+
+ qCDebug(PX4ParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile;
- Q_ASSERT(_mapParameterName2FactMetaData.count() == 0);
+ QFile xmlFile(metaDataFile);
- QString parameterFilename;
-
- // We want unit test builds to always use the resource based meta data to provide repeatable results
- if (!qgcApp()->runningUnitTests()) {
- // First look for meta data that comes from a firmware download. Fall back to resource if not there.
- parameterFilename = parameterMetaDataFile();
+ if (!xmlFile.exists()) {
+ qWarning() << "Internal error: metaDataFile mission" << metaDataFile;
+ return;
}
- if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
- parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml";
- }
-
- qCDebug(PX4ParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename;
-
- QFile xmlFile(parameterFilename);
- Q_ASSERT(xmlFile.exists());
- bool success = xmlFile.open(QIODevice::ReadOnly);
- Q_UNUSED(success);
- Q_ASSERT(success);
+ if (!xmlFile.open(QIODevice::ReadOnly)) {
+ qWarning() << "Internal error: Unable to open parameter file:" << metaDataFile << xmlFile.errorString();
+ return;
+ }
QXmlStreamReader xml(xmlFile.readAll());
xmlFile.close();
@@ -159,15 +139,19 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
}
if (intVersion <= 2) {
// We can't read these old files
- qDebug() << "Parameter version stamp too old, skipping load. Found:" << intVersion << "Want: 3 File:" << parameterFilename;
+ qDebug() << "Parameter version stamp too old, skipping load. Found:" << intVersion << "Want: 3 File:" << metaDataFile;
return;
}
-
+ } else if (elementName == "parameter_version_major") {
+ // Just skip over for now
+ } else if (elementName == "parameter_version_minor") {
+ // Just skip over for now
+
} else if (elementName == "group") {
if (xmlState != XmlStateFoundVersion) {
// We didn't get a version stamp, assume older version we can't read
- qDebug() << "Parameter version stamp not found, skipping load" << parameterFilename;
+ qDebug() << "Parameter version stamp not found, skipping load" << metaDataFile;
return;
}
xmlState = XmlStateFoundGroup;
@@ -354,17 +338,69 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
}
}
-/// Override from FactLoad which connects the meta data to the fact
void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{
Q_UNUSED(vehicleType)
- _loadParameterFactMetaData();
if (_mapParameterName2FactMetaData.contains(fact->name())) {
fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]);
- } else {
- // Use generic meta data
- FactMetaData* metaData = new FactMetaData(fact->type(), fact);
- fact->setMetaData(metaData);
+ }
+}
+
+void PX4ParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
+{
+ QFile xmlFile(metaDataFile);
+
+ if (!xmlFile.exists()) {
+ qWarning() << "Internal error: metaDataFile mission" << metaDataFile;
+ return;
+ }
+
+ if (!xmlFile.open(QIODevice::ReadOnly)) {
+ qWarning() << "Internal error: Unable to open parameter file:" << metaDataFile << xmlFile.errorString();
+ return;
+ }
+
+ QXmlStreamReader xml(xmlFile.readAll());
+ xmlFile.close();
+ if (xml.hasError()) {
+ qWarning() << "Badly formed XML" << xml.errorString();
+ return;
+ }
+
+ majorVersion = -1;
+ minorVersion = -1;
+
+ while (!xml.atEnd() && (majorVersion == -1 || minorVersion == -1)) {
+ if (xml.isStartElement()) {
+ QString elementName = xml.name().toString();
+
+ if (elementName == "parameter_version_major") {
+ bool convertOk;
+ QString strVersion = xml.readElementText();
+ majorVersion = strVersion.toInt(&convertOk);
+ if (!convertOk) {
+ qWarning() << "Badly formed XML";
+ return;
+ }
+ } else if (elementName == "parameter_version_minor") {
+ bool convertOk;
+ QString strVersion = xml.readElementText();
+ minorVersion = strVersion.toInt(&convertOk);
+ if (!convertOk) {
+ qWarning() << "Badly formed XML";
+ return;
+ }
+ }
+ }
+ xml.readNext();
+ }
+
+ // Assume defaults if not found
+ if (majorVersion == -1) {
+ majorVersion = 1;
+ }
+ if (minorVersion == -1) {
+ minorVersion = 1;
}
}
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
index 4c9859f..f2cee1a 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
+++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h
@@ -38,19 +38,18 @@
Q_DECLARE_LOGGING_CATEGORY(PX4ParameterMetaDataLog)
-/// Collection of Parameter Facts for PX4 AutoPilot
-
+/// Loads and holds parameter fact meta data for PX4 stack
class PX4ParameterMetaData : public QObject
{
Q_OBJECT
public:
- PX4ParameterMetaData(QObject* parent = NULL);
+ PX4ParameterMetaData(void);
- void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
+ void loadParameterFactMetaDataFile (const QString& metaDataFile);
+ void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType);
- /// @return Location of PX4 parameter meta data file
- static QString parameterMetaDataFile(void);
+ static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
private:
enum {
@@ -62,11 +61,10 @@ private:
XmlStateDone
};
- static void _loadParameterFactMetaData(void);
- static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
+ QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
- static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
- static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
+ bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
+ QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
};
#endif
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index ca6bdc3..a79e10d 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -74,7 +74,6 @@
#include "VehicleComponent.h"
#include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h"
-#include "Generic/GenericFirmwarePlugin.h"
#include "APM/ArduCopterFirmwarePlugin.h"
#include "APM/ArduPlaneFirmwarePlugin.h"
#include "APM/ArduRoverFirmwarePlugin.h"
@@ -372,8 +371,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
settings.clear();
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
- QFile::remove(PX4AirframeLoader::aiframeMetaDataFile());
- QFile::remove(PX4ParameterMetaData::parameterMetaDataFile());
+ // Clear parameter cache
QDir paramDir(ParameterLoader::parameterCacheDir());
paramDir.removeRecursively();
paramDir.mkpath(paramDir.absolutePath());
diff --git a/src/QGCLoggingCategory.cc b/src/QGCLoggingCategory.cc
index f053d13..175c123 100644
--- a/src/QGCLoggingCategory.cc
+++ b/src/QGCLoggingCategory.cc
@@ -31,6 +31,7 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
+QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
QGCLoggingCategoryRegister* _instance = NULL;
diff --git a/src/QGCLoggingCategory.h b/src/QGCLoggingCategory.h
index 4989b2a..f1c073e 100644
--- a/src/QGCLoggingCategory.h
+++ b/src/QGCLoggingCategory.h
@@ -35,6 +35,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
+Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc
index 37cd834..82973dc 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.cc
+++ b/src/QmlControls/QGroundControlQmlGlobal.cc
@@ -55,6 +55,9 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
_offlineEditingFirmwareTypeMetaData.setEnumInfo(firmwareEnumStrings, firmwareEnumValues);
_offlineEditingFirmwareTypeFact.setMetaData(&_offlineEditingFirmwareTypeMetaData);
+
+ // We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown.
+ setParent(NULL);
}
QGroundControlQmlGlobal::~QGroundControlQmlGlobal()
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 14db6c2..e0032af 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -189,7 +189,7 @@ Vehicle::Vehicle(LinkInterface* link,
_missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
- _parameterLoader = new ParameterLoader(_autopilotPlugin, this /* Vehicle */, this /* parent */);
+ _parameterLoader = new ParameterLoader(this);
connect(_parameterLoader, &ParameterLoader::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 96d43c3..9c87184 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -641,6 +641,7 @@ private:
bool _mapTrajectoryHaveFirstCoordinate;
static const int _mapTrajectoryMsecsBetweenPoints = 1000;
+ // Toolbox references
FirmwarePluginManager* _firmwarePluginManager;
AutoPilotPluginManager* _autopilotPluginManager;
JoystickManager* _joystickManager;
diff --git a/src/VehicleSetup/FirmwareImage.cc b/src/VehicleSetup/FirmwareImage.cc
index 1beac43..f25b438 100644
--- a/src/VehicleSetup/FirmwareImage.cc
+++ b/src/VehicleSetup/FirmwareImage.cc
@@ -27,6 +27,11 @@
#include "FirmwareImage.h"
#include "QGCLoggingCategory.h"
+#include "JsonHelper.h"
+#include "QGCMAVLink.h"
+#include "QGCApplication.h"
+#include "FirmwarePlugin.h"
+#include "ParameterLoader.h"
#include
#include
@@ -37,6 +42,15 @@
#include
#include
+const char* FirmwareImage::_jsonBoardIdKey = "board_id";
+const char* FirmwareImage::_jsonParamXmlSizeKey = "parameter_xml_size";
+const char* FirmwareImage::_jsonParamXmlKey = "parameter_xml";
+const char* FirmwareImage::_jsonAirframeXmlSizeKey = "airframe_xml_size";
+const char* FirmwareImage::_jsonAirframeXmlKey = "airframe_xml";
+const char* FirmwareImage::_jsonImageSizeKey = "image_size";
+const char* FirmwareImage::_jsonImageKey = "image";
+const char* FirmwareImage::_jsonMavAutopilotKey = "mav_autopilot";
+
FirmwareImage::FirmwareImage(QObject* parent) :
QObject(parent),
_imageSize(0)
@@ -217,38 +231,52 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QJsonObject px4Json = doc.object();
// Make sure the keys we need are available
- static const char* rgJsonKeys[] = { "board_id", "image_size", "description", "git_identity" };
- for (size_t i=0; i types;
+ keys << _jsonBoardIdKey << _jsonParamXmlSizeKey << _jsonParamXmlKey << _jsonAirframeXmlSizeKey << _jsonAirframeXmlKey << _jsonImageSizeKey << _jsonImageKey << _jsonMavAutopilotKey;
+ types << QJsonValue::Double << QJsonValue::Double << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::Double << QJsonValue::String << QJsonValue::Double;
+ if (!JsonHelper::validateKeyTypes(px4Json, keys, types, errorString)) {
+ emit errorMessage(QString("Firmware file has invalid key: %1").arg(errorString));
+ return false;
+ }
+
+ uint32_t firmwareBoardId = (uint32_t)px4Json.value(_jsonBoardIdKey).toInt();
if (firmwareBoardId != _boardId) {
emit errorMessage(QString("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardId).arg(_boardId));
return false;
}
+
+ // What firmware type is this?
+ MAV_AUTOPILOT firmwareType = (MAV_AUTOPILOT)px4Json[_jsonMavAutopilotKey].toInt(MAV_AUTOPILOT_PX4);
+ emit statusMessage(QString("MAV_AUTOPILOT = %1").arg(firmwareType));
// Decompress the parameter xml and save to file
QByteArray decompressedBytes;
bool success = _decompressJsonValue(px4Json, // JSON object
bytes, // Raw bytes of JSON document
- "parameter_xml_size", // key which holds byte size
- "parameter_xml", // key which holds compress bytes
+ _jsonParamXmlSizeKey, // key which holds byte size
+ _jsonParamXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (success) {
- // We cache the parameter xml in the same location as settings
+ // Use settings location as our work directory, this way is something goes wrong the file is still there
+ // sitting next to the cache files.
QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
- QString parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml");
+ QString parameterFilename = parameterDir.filePath("ParameterFactMetaData.xml");
QFile parameterFile(parameterFilename);
if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = parameterFile.write(decompressedBytes);
if (bytesWritten != decompressedBytes.count()) {
- // FIXME: What about these warnings?
emit statusMessage(QString("Write failed for parameter meta data file, error: %1").arg(parameterFile.errorString()));
parameterFile.close();
QFile::remove(parameterFilename);
@@ -258,14 +286,17 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
} else {
emit statusMessage(QString("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename).arg(parameterFile.errorString()));
}
+
+ // Cache this file with the system
+ ParameterLoader::cacheMetaDataFile(parameterFilename, firmwareType);
}
// Decompress the airframe xml and save to file
- success = _decompressJsonValue(px4Json, // JSON object
- bytes, // Raw bytes of JSON document
- "airframe_xml_size", // key which holds byte size
- "airframe_xml", // key which holds compress bytes
- decompressedBytes); // Returned decompressed bytes
+ success = _decompressJsonValue(px4Json, // JSON object
+ bytes, // Raw bytes of JSON document
+ _jsonAirframeXmlSizeKey, // key which holds byte size
+ _jsonAirframeXmlKey, // key which holds compressed bytes
+ decompressedBytes); // Returned decompressed bytes
if (success) {
// We cache the airframe xml in the same location as settings and parameters
QSettings settings;
@@ -293,8 +324,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_imageSize = px4Json.value(QString("image_size")).toInt();
success = _decompressJsonValue(px4Json, // JSON object
bytes, // Raw bytes of JSON document
- "image_size", // key which holds byte size
- "image", // key which holds compress bytes
+ _jsonImageSizeKey, // key which holds byte size
+ _jsonImageKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes
if (!success) {
return false;
@@ -341,7 +372,7 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
}
int decompressedSize = jsonObject.value(QString(sizeKey)).toInt();
if (decompressedSize == 0) {
- emit errorMessage(QString("Firmware file has invalid decompressed size for %1").arg(sizeKey));
+ emit statusMessage(QString("Firmware file has invalid decompressed size for %1").arg(sizeKey));
return false;
}
@@ -353,12 +384,12 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
QStringList parts = QString(jsonDocBytes).split(QString("\"%1\": \"").arg(bytesKey));
if (parts.count() == 1) {
- emit errorMessage(QString("Could not find compressed bytes for %1 in Firmware file").arg(bytesKey));
+ emit statusMessage(QString("Could not find compressed bytes for %1 in Firmware file").arg(bytesKey));
return false;
}
parts = parts.last().split("\"");
if (parts.count() == 1) {
- emit errorMessage(QString("Incorrectly formed compressed bytes section for %1 in Firmware file").arg(bytesKey));
+ emit statusMessage(QString("Incorrectly formed compressed bytes section for %1 in Firmware file").arg(bytesKey));
return false;
}
@@ -374,11 +405,11 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
decompressedBytes = qUncompress(raw);
if (decompressedBytes.count() == 0) {
- emit errorMessage(QString("Firmware file has 0 length %1").arg(bytesKey));
+ emit statusMessage(QString("Firmware file has 0 length %1").arg(bytesKey));
return false;
}
if (decompressedBytes.count() != decompressedSize) {
- emit errorMessage(QString("Size for decompressed %1 does not match stored size: Expected(%1) Actual(%2)").arg(decompressedSize).arg(decompressedBytes.count()));
+ emit statusMessage(QString("Size for decompressed %1 does not match stored size: Expected(%1) Actual(%2)").arg(decompressedSize).arg(decompressedBytes.count()));
return false;
}
diff --git a/src/VehicleSetup/FirmwareImage.h b/src/VehicleSetup/FirmwareImage.h
index 6c3467d..0ec9e44 100644
--- a/src/VehicleSetup/FirmwareImage.h
+++ b/src/VehicleSetup/FirmwareImage.h
@@ -98,6 +98,15 @@ private:
QString _binFilename;
QList _ihxBlocks;
uint32_t _imageSize;
+
+ static const char* _jsonBoardIdKey;
+ static const char* _jsonParamXmlSizeKey;
+ static const char* _jsonParamXmlKey;
+ static const char* _jsonAirframeXmlSizeKey;
+ static const char* _jsonAirframeXmlKey;
+ static const char* _jsonImageSizeKey;
+ static const char* _jsonImageKey;
+ static const char* _jsonMavAutopilotKey;
};
#endif
diff --git a/src/comm/PX4MockLink.params b/src/comm/PX4MockLink.params
index 5ecb10c..34531ba 100644
--- a/src/comm/PX4MockLink.params
+++ b/src/comm/PX4MockLink.params
@@ -508,6 +508,7 @@
1 50 SYS_AUTOCONFIG 0 6
1 50 SYS_AUTOSTART 10016 6
1 50 SYS_COMPANION 157600 6
+1 50 SYS_PARAM_VER 1 6
1 50 SYS_RESTART_TYPE 0 6
1 50 SYS_USE_IO 1 6
1 50 TEST_D 0.01 9