Commit bf6599e4 authored by Don Gagne's avatar Don Gagne

Versioned parameter meta data cache

parent 8d0b28f0
...@@ -231,13 +231,15 @@ ...@@ -231,13 +231,15 @@
</qresource> </qresource>
<qresource prefix="/AutoPilotPlugins/PX4"> <qresource prefix="/AutoPilotPlugins/PX4">
<file alias="AirframeFactMetaData.xml">src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml</file> <file alias="AirframeFactMetaData.xml">src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml</file>
<file alias="ParameterFactMetaData.xml">src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml</file>
</qresource> </qresource>
<qresource prefix="/AutoPilotPlugins/APM"> <qresource prefix="/AutoPilotPlugins/APM">
<file alias="APMAirframeFactMetaData.xml">src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml</file> <file alias="APMAirframeFactMetaData.xml">src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml</file>
</qresource> </qresource>
<qresource prefix="/FirmwarePlugin/APM"> <qresource prefix="/FirmwarePlugin/APM">
<file alias="apm.pdef.xml">src/FirmwarePlugin/APM/apm.pdef.xml</file> <file alias="APMParameterFactMetaData.xml">src/FirmwarePlugin/APM/APMParameterFactMetaData.xml</file>
</qresource>
<qresource prefix="/FirmwarePlugin/PX4">
<file alias="PX4ParameterFactMetaData.xml">src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml</file>
</qresource> </qresource>
<qresource prefix="/opengl"> <qresource prefix="/opengl">
<file>resources/opengl/buglist.json</file> <file>resources/opengl/buglist.json</file>
......
...@@ -606,7 +606,6 @@ HEADERS+= \ ...@@ -606,7 +606,6 @@ HEADERS+= \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \ src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
src/Vehicle/MultiVehicleManager.h \ src/Vehicle/MultiVehicleManager.h \
...@@ -661,8 +660,8 @@ SOURCES += \ ...@@ -661,8 +660,8 @@ SOURCES += \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \ src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/MultiVehicleManager.cc \
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "GenericAutoPilotPlugin.h" #include "GenericAutoPilotPlugin.h"
#include "FirmwarePlugin/Generic/GenericFirmwarePlugin.h" // FIXME: Hack
GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent) AutoPilotPlugin(vehicle, parent)
......
<?xml version='1.0' encoding='UTF-8'?> <?xml version='1.0' encoding='UTF-8'?>
<airframes> <airframes>
<version>1</version> <version>1</version>
<airframe_version_minor>1</airframe_version_minor>
<airframe_group image="HelicopterCoaxial" name="Coaxial Helicopter"> <airframe_group image="HelicopterCoaxial" name="Coaxial Helicopter">
<airframe id="15001" maintainer="Emmanuel Roussel" name="Coaxial Helicopter (such as Esky Lama v4 or Esky Big Lama)"> <airframe id="15001" maintainer="Emmanuel Roussel" name="Coaxial Helicopter (such as Esky Lama v4 or Esky Big Lama)">
<maintainer>Emmanuel Roussel</maintainer> <maintainer>Emmanuel Roussel</maintainer>
...@@ -230,6 +231,13 @@ ...@@ -230,6 +231,13 @@
<maintainer>Blankered</maintainer> <maintainer>Blankered</maintainer>
<type>Quadrotor x</type> <type>Quadrotor x</type>
</airframe> </airframe>
<airframe id="4050" maintainer="Mark Whitehorn &lt;kd0aij@gmail.com&gt;" name="Generic 250 Racer">
<maintainer>Mark Whitehorn &lt;kd0aij@gmail.com&gt;</maintainer>
<type>Quadrotor x</type>
<output name="AUX1">feed-through of RC AUX1 channel</output>
<output name="AUX2">feed-through of RC AUX2 channel</output>
<output name="AUX3">feed-through of RC AUX3 channel</output>
</airframe>
</airframe_group> </airframe_group>
<airframe_group image="Rover" name="Rover"> <airframe_group image="Rover" name="Rover">
<airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10"> <airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10">
......
...@@ -134,6 +134,10 @@ void PX4AirframeLoader::loadAirframeMetaData(void) ...@@ -134,6 +134,10 @@ void PX4AirframeLoader::loadAirframeMetaData(void)
return; 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") { } else if (elementName == "airframe_group") {
if (xmlState != XmlStateFoundVersion) { if (xmlState != XmlStateFoundVersion) {
......
This diff is collapsed.
...@@ -40,7 +40,6 @@ ...@@ -40,7 +40,6 @@
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog) Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog)
/// Connects to Parameter Manager to load/update Facts /// Connects to Parameter Manager to load/update Facts
...@@ -50,7 +49,7 @@ class ParameterLoader : public QObject ...@@ -50,7 +49,7 @@ class ParameterLoader : public QObject
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); ParameterLoader(Vehicle* vehicle);
~ParameterLoader(); ~ParameterLoader();
...@@ -91,6 +90,19 @@ public: ...@@ -91,6 +90,19 @@ public:
QString readParametersFromStream(QTextStream& stream); QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(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: signals:
/// Signalled when the full set of facts are ready /// Signalled when the full set of facts are ready
...@@ -103,7 +115,6 @@ signals: ...@@ -103,7 +115,6 @@ signals:
void restartWaitingParamTimer(void); void restartWaitingParamTimer(void);
protected: protected:
AutoPilotPlugin* _autopilot;
Vehicle* _vehicle; Vehicle* _vehicle;
MAVLinkProtocol* _mavlink; MAVLinkProtocol* _mavlink;
...@@ -123,6 +134,7 @@ private: ...@@ -123,6 +134,7 @@ private:
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int uasId, int componentId); void _writeLocalParamCache(int uasId, int componentId);
void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value); void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
void _addMetaDataToAll(void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType); FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
...@@ -134,18 +146,22 @@ private: ...@@ -134,18 +146,22 @@ private:
/// First mapping is by component id /// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant /// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant; QMap<int, QVariantMap> _mapParameterName2Variant;
QMap<int, QMap<int, QString> > _mapParameterId2Name; QMap<int, QMap<int, QString> > _mapParameterId2Name;
/// First mapping is by component id /// First mapping is by component id
/// Second mapping is group name, to Fact /// Second mapping is group name, to Fact
QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName; QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName;
bool _parametersReady; ///< true: full set of parameters correctly loaded bool _parametersReady; ///< true: full set of parameters correctly loaded
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
bool _saveRequired; ///< true: _saveToEEPROM should be called bool _saveRequired; ///< true: _saveToEEPROM should be called
int _defaultComponentId; int _defaultComponentId;
QString _defaultComponentIdParam; 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 static const int _maxInitialLoadRetry = 10; ///< Maximum a retries on initial index based load
QMap<int, int> _paramCountMap; ///< Key: Component id, Value: count of parameters in this component QMap<int, int> _paramCountMap; ///< Key: Component id, Value: count of parameters in this component
...@@ -162,6 +178,8 @@ private: ...@@ -162,6 +178,8 @@ private:
QMutex _dataMutex; QMutex _dataMutex;
static Fact _defaultFact; ///< Used to return default fact, when parameter not found static Fact _defaultFact; ///< Used to return default fact, when parameter not found
static const char* _cachedMetaDataFilePrefix;
}; };
#endif #endif
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "APMFirmwarePlugin.h" #include "APMFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack #include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCApplication.h" #include "QGCApplication.h"
...@@ -473,11 +472,16 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -473,11 +472,16 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return true; 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<APMParameterMetaData*>(parameterMetaData);
}
if (apmMetaData) {
apmMetaData->addMetaDataToFact(fact, vehicleType);
} else {
qWarning() << "Internal error: pointer passed to APMFirmwarePlugin::addMetaDataToFact not APMParameterMetaData";
}
}
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void) QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{ {
...@@ -508,3 +512,11 @@ void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt ...@@ -508,3 +512,11 @@ void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt
fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json"); fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json"); multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
} }
QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
Q_UNUSED(metaDataFile);
APMParameterMetaData* metaData = new APMParameterMetaData;
return metaData;
}
...@@ -80,19 +80,25 @@ class APMFirmwarePlugin : public FirmwarePlugin ...@@ -80,19 +80,25 @@ class APMFirmwarePlugin : public FirmwarePlugin
public: public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
virtual bool isCapable(FirmwareCapabilities capabilities);
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle); QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
virtual QStringList flightModes(void); QList<MAV_CMD> supportedMissionCommands(void) final;
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); bool isCapable(FirmwareCapabilities capabilities) final;
virtual int manualControlReservedButtonCount(void); QStringList flightModes(void) final;
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
virtual void initializeVehicle(Vehicle* vehicle); bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
virtual bool sendHomePositionToVehicle(void); int manualControlReservedButtonCount(void) final;
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } void initializeVehicle(Vehicle* vehicle) final;
virtual QList<MAV_CMD> supportedMissionCommands(void); bool sendHomePositionToVehicle(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const 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: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation
...@@ -109,7 +115,6 @@ private: ...@@ -109,7 +115,6 @@ private:
APMFirmwareVersion _firmwareVersion; APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded; bool _textSeverityAdjustmentNeeded;
QList<APMCustomMode> _supportedModes; QList<APMCustomMode> _supportedModes;
APMParameterMetaData _parameterMetaData;
}; };
#endif #endif
...@@ -21,9 +21,6 @@ ...@@ -21,9 +21,6 @@
======================================================================*/ ======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "APMParameterMetaData.h" #include "APMParameterMetaData.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
...@@ -34,15 +31,13 @@ ...@@ -34,15 +31,13 @@
#include <QDebug> #include <QDebug>
#include <QStack> #include <QStack>
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog") QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog") QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
bool APMParameterMetaData::_parameterMetaDataLoaded = false;
QMap<QString, ParameterNametoFactMetaDataMap> APMParameterMetaData::_vehicleTypeToParametersMap;
APMParameterMetaData::APMParameterMetaData(QObject* parent) : APMParameterMetaData::APMParameterMetaData(void)
QObject(parent) : _parameterMetaDataLoaded(false)
{ {
// APM meta data is not yet versioned
_loadParameterFactMetaData(); _loadParameterFactMetaData();
} }
...@@ -146,7 +141,7 @@ void APMParameterMetaData::_loadParameterFactMetaData() ...@@ -146,7 +141,7 @@ void APMParameterMetaData::_loadParameterFactMetaData()
// Fixme:: always picking up the bundled xml, we would like to update it from web // 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. // just not sure right now as the xml is in bad shape.
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) { if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
parameterFilename = ":/FirmwarePlugin/APM/apm.pdef.xml"; parameterFilename = ":/FirmwarePlugin/APM/APMParameterFactMetaData.xml";
} }
qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename; qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename;
...@@ -428,11 +423,8 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa ...@@ -428,11 +423,8 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa
return true; return true;
} }
/// Override from FactLoad which connects the meta data to the fact
void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{ {
_loadParameterFactMetaData();
const QString mavTypeString = mavTypeToString(vehicleType); const QString mavTypeString = mavTypeToString(vehicleType);
APMFactMetaDataRaw* rawMetaData = NULL; APMFactMetaDataRaw* rawMetaData = NULL;
...@@ -591,3 +583,12 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) ...@@ -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 // FixMe:: not handling increment size as their is no place for it in FactMetaData and no ui
fact->setMetaData(metaData); fact->setMetaData(metaData);
} }
void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
Q_UNUSED(metaDataFile);
// Versioning not yet supported
majorVersion = -1;
minorVersion = -1;
}
...@@ -34,6 +34,9 @@ ...@@ -34,6 +34,9 @@
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "Vehicle.h" #include "Vehicle.h"
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
class APMFactMetaDataRaw class APMFactMetaDataRaw
{ {
public: public:
...@@ -54,11 +57,6 @@ public: ...@@ -54,11 +57,6 @@ public:
QList<QPair<QString, QString> > bitmask; QList<QPair<QString, QString> > bitmask;
}; };
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
/// Collection of Parameter Facts for PX4 AutoPilot /// Collection of Parameter Facts for PX4 AutoPilot
...@@ -69,15 +67,11 @@ class APMParameterMetaData : public QObject ...@@ -69,15 +67,11 @@ class APMParameterMetaData : public QObject
Q_OBJECT Q_OBJECT
public: public:
/// @param uas Uas which this set of facts is associated with APMParameterMetaData(void);
APMParameterMetaData(QObject* parent = NULL);
/// Override from ParameterLoader void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
// Overrides from ParameterLoader
static void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
static void addMetaDataToFacts(QVariantMap &facts, MAV_TYPE vehicleType);
private: private:
enum { enum {
...@@ -90,18 +84,17 @@ private: ...@@ -90,18 +84,17 @@ private:
XmlStateFoundGroup, XmlStateFoundGroup,
XmlStateFoundParameter, XmlStateFoundParameter,
XmlStateDone XmlStateDone
}; };
static void _loadParameterFactMetaData(); void _loadParameterFactMetaData();
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 skipXMLBlock(QXmlStreamReader& xml, const QString& blockName); bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
static bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData); bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
static void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap<QString,QStringList>& groupMembers); void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap<QString,QStringList>& groupMembers);
static QString mavTypeToString(MAV_TYPE vehicleTypeEnum); QString mavTypeToString(MAV_TYPE vehicleTypeEnum);
static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
static QMap<QString, ParameterNametoFactMetaDataMap> _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map> QMap<QString, ParameterNametoFactMetaDataMap> _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map>
}; };
#endif #endif
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "ArduCopterFirmwarePlugin.h" #include "ArduCopterFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable) APMCustomMode(mode, settable)
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com> /// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduPlaneFirmwarePlugin.h" #include "ArduPlaneFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable) : APMCustomMode(mode, settable)
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com> /// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduRoverFirmwarePlugin.h" #include "ArduRoverFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMRoverMode::APMRoverMode(uint32_t mode, bool settable) APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable) : APMCustomMode(mode, settable)
......
...@@ -21,22 +21,18 @@ ...@@ -21,22 +21,18 @@
======================================================================*/ ======================================================================*/
/// @file #include "FirmwarePlugin.h"
/// @author Don Gagne <don@thegagnes.com>
#include "GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h" // FIXME: Hack
#include <QDebug> #include <QDebug>
QList<VehicleComponent*> GenericFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) QList<VehicleComponent*> FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
return QList<VehicleComponent*>(); return QList<VehicleComponent*>();
} }
QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode)
{ {
QString flightMode; QString flightMode;
...@@ -72,25 +68,25 @@ QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mod ...@@ -72,25 +68,25 @@ QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mod
return flightMode; 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(flightMode);
Q_UNUSED(base_mode); Q_UNUSED(base_mode);
Q_UNUSED(custom_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; 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. // We don't know whether the firmware is going to used any of these buttons.
// So reserve them all. // So reserve them all.
return -1; 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(vehicle);
Q_UNUSED(message); Q_UNUSED(message);
...@@ -98,14 +94,14 @@ void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_messa ...@@ -98,14 +94,14 @@ void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_messa
// Generic plugin does no message adjustment // Generic plugin does no message adjustment
} }
void GenericFirmwarePlugin::initializeVehicle(Vehicle* vehicle) void FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
// Generic Flight Stack is by definition "generic", so no extra work // 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. // Generic stack does not want home position sent in the first position.
// Subsequent sequence numbers must be adjusted. // Subsequent sequence numbers must be adjusted.
...@@ -113,25 +109,23 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -113,25 +109,23 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return false; return false;
} }
void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
{
Q_UNUSED(vehicleType)
// Add default meta data
FactMetaData* metaData = new FactMetaData(fact->type(), fact);
fact->setMetaData(metaData);
}
QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
{ {
// Generic supports all commands // Generic supports all commands
return QList<MAV_CMD>(); return QList<MAV_CMD>();
} }
void GenericFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const void FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{ {
// No overrides // No overrides
commonJsonFilename.clear(); commonJsonFilename.clear();
fixedWingJsonFilename.