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.clear(); fixedWingJsonFilename.clear();
multiRotorJsonFilename.clear(); multiRotorJsonFilename.clear();
} }
void FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
Q_UNUSED(metaDataFile);
majorVersion = -1;
minorVersion = -1;
}
...@@ -38,12 +38,10 @@ class Vehicle; ...@@ -38,12 +38,10 @@ class Vehicle;
/// This is the base class for Firmware specific plugins /// This is the base class for Firmware specific plugins
/// ///
/// The FirmwarePlugin class is the abstract base class which represents the methods and objects /// The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack.
/// which are specific to a certain Firmware flight stack. This is the only place where /// This is the only place where flight stack specific code should reside in QGroundControl. The remainder of the
/// 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
/// QGroundControl source is generic to a common mavlink implementation. The implementation /// mavlink generic firmware. Override the base clase virtuals to create your own firmware specific plugin.
/// in the base class supports mavlink generic firmware. Override the base clase virtuals
/// to create you firmware specific plugin.
class FirmwarePlugin : public QObject class FirmwarePlugin : public QObject
{ {
...@@ -53,31 +51,30 @@ public: ...@@ -53,31 +51,30 @@ public:
/// Set of optional capabilites which firmware may support /// Set of optional capabilites which firmware may support
typedef enum { typedef enum {
SetFlightModeCapability, ///< FirmwarePlugin::setFlightMode method is supported SetFlightModeCapability, ///< FirmwarePlugin::setFlightMode method is supported
MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
} FirmwareCapabilities; } FirmwareCapabilities;
/// @return true: Firmware supports all specified capabilites /// @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 /// Returns VehicleComponents for specified Vehicle
/// @param vehicle Vehicle to associate with components /// @param vehicle Vehicle to associate with components
/// @return List of VehicleComponents for the specified vehicle. Caller owns returned objects and must /// @return List of VehicleComponents for the specified vehicle. Caller owns returned objects and must
/// free when no longer needed. /// free when no longer needed.
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) = 0; virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
/// Returns the list of available flight modes /// 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. /// 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 base_mode Base mode from mavlink HEARTBEAT message
/// @param custom_mode Custom 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. /// Sets base_mode and custom_mode to specified flight mode.
/// @param[out] base_mode Base mode for SET_MODE mavlink message /// @param[out] base_mode Base mode for SET_MODE mavlink message
/// @param[out] custom_mode Custom 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 /// 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. /// not just this. I'm going to try to change that. If not, this will need to be removed.
...@@ -85,17 +82,17 @@ public: ...@@ -85,17 +82,17 @@ public:
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
/// The remainder can be assigned to Vehicle actions. /// The remainder can be assigned to Vehicle actions.
/// @return -1: reserver all buttons, >0 number of buttons to reserve /// @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 /// 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 /// 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. /// spec implementations such that the base code can remain mavlink generic.
/// @param vehicle Vehicle message came from /// @param vehicle Vehicle message came from
/// @param message[in,out] Mavlink message to adjust if needed. /// @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. /// 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 /// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position. /// is always the home position.
...@@ -103,22 +100,38 @@ public: ...@@ -103,22 +100,38 @@ public:
/// true: Send first mission item as home position to vehicle. When vehicle has no mission items on /// 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. /// 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 /// 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 /// 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 /// 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. /// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void) = 0; virtual QList<MAV_CMD> supportedMissionCommands(void);
/// Returns the names for the mission command json override files. Empty string to specify no overrides. /// 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] commonJsonFilename Filename for common overrides
/// @param[out] fixedWingJsonFilename Filename for fixed wing overrides /// @param[out] fixedWingJsonFilename Filename for fixed wing overrides
/// @param[out] multiRotorJsonFilename Filename for multi rotor 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 #endif
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FirmwarePluginManager.h" #include "FirmwarePluginManager.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "APM/ArduCopterFirmwarePlugin.h" #include "APM/ArduCopterFirmwarePlugin.h"
#include "APM/ArduPlaneFirmwarePlugin.h" #include "APM/ArduPlaneFirmwarePlugin.h"
#include "APM/ArduRoverFirmwarePlugin.h" #include "APM/ArduRoverFirmwarePlugin.h"
...@@ -91,7 +90,12 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT ...@@ -91,7 +90,12 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT
} }
if (!_genericFirmwarePlugin) { if (!_genericFirmwarePlugin) {
_genericFirmwarePlugin = new GenericFirmwarePlugin; _genericFirmwarePlugin = new FirmwarePlugin;
} }
return _genericFirmwarePlugin; return _genericFirmwarePlugin;
} }
void FirmwarePluginManager::clearSettings(void)
{
// FIXME: NYI
}
...@@ -38,7 +38,6 @@ class ArduCopterFirmwarePlugin; ...@@ -38,7 +38,6 @@ class ArduCopterFirmwarePlugin;
class ArduPlaneFirmwarePlugin; class ArduPlaneFirmwarePlugin;
class ArduRoverFirmwarePlugin; class ArduRoverFirmwarePlugin;
class PX4FirmwarePlugin; class PX4FirmwarePlugin;
class GenericFirmwarePlugin;
/// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type. /// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type.
...@@ -56,11 +55,14 @@ public: ...@@ -56,11 +55,14 @@ public:
/// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT. /// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT.
FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType); FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType);
/// Clears settings from all firmware plugins.
void clearSettings(void);
private: private:
ArduCopterFirmwarePlugin* _arduCopterFirmwarePlugin; ArduCopterFirmwarePlugin* _arduCopterFirmwarePlugin;
ArduPlaneFirmwarePlugin* _arduPlaneFirmwarePlugin; ArduPlaneFirmwarePlugin* _arduPlaneFirmwarePlugin;
ArduRoverFirmwarePlugin* _arduRoverFirmwarePlugin; ArduRoverFirmwarePlugin* _arduRoverFirmwarePlugin;
GenericFirmwarePlugin* _genericFirmwarePlugin; FirmwarePlugin* _genericFirmwarePlugin;
PX4FirmwarePlugin* _px4FirmwarePlugin; PX4FirmwarePlugin* _px4FirmwarePlugin;
}; };
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#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<VehicleComponent*> 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<MAV_CMD> supportedMissionCommands(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
};
#endif
...@@ -25,6 +25,7 @@ ...@@ -25,6 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "PX4FirmwarePlugin.h" #include "PX4FirmwarePlugin.h"
#include "PX4ParameterMetaData.h"
#include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h" // FIXME: Hack #include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h" // FIXME: Hack
#include <QDebug> #include <QDebug>
...@@ -204,9 +205,15 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -204,9 +205,15 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return false; 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<PX4ParameterMetaData*>(parameterMetaData);
if (px4MetaData) {
px4MetaData->addMetaDataToFact(fact, vehicleType);
} else {
qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData";
}
} }
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
...@@ -233,3 +240,10 @@ void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt ...@@ -233,3 +240,10 @@ void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt
fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json"); fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json"); multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
} }
QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
PX4ParameterMetaData* metaData = new PX4ParameterMetaData;
metaData->loadParameterFactMetaDataFile(metaDataFile);
return metaData;
}
...@@ -28,6 +28,7 @@ ...@@ -28,6 +28,7 @@
#define PX4FirmwarePlugin_H #define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include "PX4ParameterMetaData.h" #include "PX4ParameterMetaData.h"
class PX4FirmwarePlugin : public FirmwarePlugin class PX4FirmwarePlugin : public FirmwarePlugin
...@@ -36,22 +37,25 @@ class PX4FirmwarePlugin : public FirmwarePlugin ...@@ -36,22 +37,25 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public: public:
// Overrides from FirmwarePlugin // Overrides from FirmwarePlugin
bool isCapable(FirmwareCapabilities capabilities) final;
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final; QList<VehicleComponent*> 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<MAV_CMD> supportedMissionCommands(void) final; QList<MAV_CMD> supportedMissionCommands(void) final;
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
private: bool isCapable (FirmwareCapabilities capabilities) final;
PX4ParameterMetaData _parameterMetaData; 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 #endif
<?xml version='1.0' encoding='UTF-8'?> <?xml version='1.0' encoding='UTF-8'?>
<parameters> <parameters>
<version>3</version> <version>3</version>
<parameter_version_major>1</parameter_version_major>
<parameter_version_minor>1</parameter_version_minor>
<group name="UAVCAN Motor Parameters" no_code_generation="true"> <group name="UAVCAN Motor Parameters" no_code_generation="true">
<parameter default="75" name="ctl_bw" type="INT32"> <parameter default="75" name="ctl_bw" type="INT32">
<short_desc>Speed controller bandwidth</short_desc> <short_desc>Speed controller bandwidth</short_desc>
...@@ -1267,21 +1269,21 @@ replay messages for logging</short_desc> ...@@ -1267,21 +1269,21 @@ replay messages for logging</short_desc>
<short_desc>Enable or disable usage of terrain estimate during landing</short_desc> <short_desc>Enable or disable usage of terrain estimate during landing</short_desc>
<long_desc>0: disabled, 1: enabled</long_desc> <long_desc>0: disabled, 1: enabled</long_desc>
</parameter> </parameter>
<parameter default="2.5" name="FW_FLARE_PMIN" type="FLOAT"> <parameter default="2.5" name="FW_LND_FL_PMIN" type="FLOAT">
<short_desc>Flare, minimum pitch</short_desc> <short_desc>Flare, minimum pitch</short_desc>
<long_desc>Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached</long_desc> <long_desc>Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached</long_desc>
<min>0</min> <min>0</min>
<max>15.0</max> <max>15.0</max>
<unit>degrees</unit> <unit>degrees</unit>
</parameter> </parameter>
<parameter default="15.0" name="FW_FLARE_PMAX" type="FLOAT"> <parameter default="15.0" name="FW_LND_FL_PMAX" type="FLOAT">
<short_desc>Flare, maximum pitch</short_desc> <short_desc>Flare, maximum pitch</short_desc>
<long_desc>Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached</long_desc> <long_desc>Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_TLALT is reached</long_desc>
<min>0</min> <min>0</min>
<max>45.0</max> <max>45.0</max>
<unit>degrees</unit> <unit>degrees</unit>
</parameter> </parameter>
<parameter default="1.3" name="FW_AIRSPD_SCALE" type="FLOAT"> <parameter default="1.3" name="FW_LND_AIRSPD_SC" type="FLOAT">
<short_desc>Landing airspeed scale factor</short_desc> <short_desc>Landing airspeed scale factor</short_desc>
<long_desc>Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach.</long_desc> <long_desc>Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach.</long_desc>
<min>1.0</min> <min>1.0</min>
...@@ -2001,7 +2003,7 @@ replay messages for logging</short_desc> ...@@ -2001,7 +2003,7 @@ replay messages for logging</short_desc>
<max>1.0</max> <max>1.0</max>
<decimal>2</decimal> <decimal>2</decimal>
</parameter> </parameter>
<parameter default="1.0" name="MPC_XY_P" type="FLOAT"> <parameter default="1.25" name="MPC_XY_P" type="FLOAT">
<short_desc>Proportional gain for horizontal position error</short_desc> <short_desc>Proportional gain for horizontal position error</short_desc>
<min>0.0</min> <min>0.0</min>
<decimal>2</decimal> <decimal>2</decimal>
...@@ -2022,12 +2024,14 @@ replay messages for logging</short_desc> ...@@ -2022,12 +2024,14 @@ replay messages for logging</short_desc>
<min>0.0</min> <min>0.0</min>
<decimal>3</decimal> <decimal>3</decimal>
</parameter> </parameter>
<parameter default="5.0" name="MPC_XY_VEL_MAX" type="FLOAT"> <parameter default="8.0" name="MPC_XY_VEL_MAX" type="FLOAT">
<short_desc>Maximum horizontal velocity</short_desc> <short_desc>Maximum horizontal velocity</short_desc>
<long_desc>Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).</long_desc> <long_desc>Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).</long_desc>
<min>0.0</min> <min>0.0</min>
<max>20.0</max>
<unit>m/s</unit> <unit>m/s</unit>
<decimal>2</decimal> <decimal>2</decimal>
<increment>1</increment>
</parameter> </parameter>
<parameter default="0.5" name="MPC_XY_FF" type="FLOAT"> <parameter default="0.5" name="MPC_XY_FF" type="FLOAT">
<short_desc>Horizontal velocity feed forward</short_desc> <short_desc>Horizontal velocity feed forward</short_desc>
...@@ -2109,12 +2113,13 @@ replay messages for logging</short_desc> ...@@ -2109,12 +2113,13 @@ replay messages for logging</short_desc>
<unit>Hz</unit> <unit>Hz</unit>
<decimal>2</decimal> <decimal>2</decimal>
</parameter> </parameter>
<parameter default="6.0" name="MPC_ACC_HOR_MAX" type="FLOAT"> <parameter default="10.0" name="MPC_ACC_HOR_MAX" type="FLOAT">
<short_desc>Maximum horizonal acceleration in velocity controlled modes</short_desc> <short_desc>Maximum horizonal acceleration in velocity controlled modes</short_desc>
<min>2.0</min> <min>2.0</min>
<max>10.0</max> <max>15.0</max>
<unit>m/s/s</unit> <unit>m/s/s</unit>
<decimal>2</decimal> <decimal>2</decimal>
<increment>1</increment>
</parameter> </parameter>
<parameter default="0.1" name="MPP_THR_MIN" type="FLOAT"> <parameter default="0.1" name="MPP_THR_MIN" type="FLOAT">
<short_desc>Minimum thrust</short_desc> <short_desc>Minimum thrust</short_desc>
......
...@@ -35,11 +35,8 @@ ...@@ -35,11 +35,8 @@
QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog") QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog")
bool PX4ParameterMetaData::_parameterMetaDataLoaded = false; PX4ParameterMetaData::PX4ParameterMetaData(void)
QMap<QString, FactMetaData*> PX4ParameterMetaData::_mapParameterName2FactMetaData; : _parameterMetaDataLoaded(false)
PX4ParameterMetaData::PX4ParameterMetaData(QObject* parent) :
QObject(parent)
{ {
} }
...@@ -78,46 +75,29 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact ...@@ -78,46 +75,29 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
return var; return var;
} }
QString PX4ParameterMetaData::parameterMetaDataFile(void) void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
{ {
QSettings settings; qCDebug(ParameterLoaderLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile;
QDir parameterDir = QFileInfo(settings.fileName()).dir();
return parameterDir.filePath("PX4ParameterFactMetaData.xml");
}
/// Load Parameter Fact meta data
///
/// The meta data comes from firmware parameters.xml file.
void PX4ParameterMetaData::_loadParameterFactMetaData(void)
{
if (_parameterMetaDataLoaded) { if (_parameterMetaDataLoaded) {
qWarning() << "Internal error: parameter meta data loaded more than once";
return; return;
} }
_parameterMetaDataLoaded = true; _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; if (!xmlFile.exists()) {
qWarning() << "Internal error: metaDataFile mission" << metaDataFile;
// We want unit test builds to always use the resource based meta data to provide repeatable results return;
if (!qgcApp()->runningUnitTests()) {
// First look for meta data that comes from a firmware download. Fall back to resource if not there.
parameterFilename = parameterMetaDataFile();
} }
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); if (!xmlFile.open(QIODevice::ReadOnly)) {
Q_UNUSED(success); qWarning() << "Internal error: Unable to open parameter file:" << metaDataFile << xmlFile.errorString();
Q_ASSERT(success); return;
}
QXmlStreamReader xml(xmlFile.readAll()); QXmlStreamReader xml(xmlFile.readAll());
xmlFile.close(); xmlFile.close();
...@@ -159,15 +139,19 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -159,15 +139,19 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void)
} }
if (intVersion <= 2) { if (intVersion <= 2) {
// We can't read these old files // 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; 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") { } else if (elementName == "group") {
if (xmlState != XmlStateFoundVersion) { if (xmlState != XmlStateFoundVersion) {
// We didn't get a version stamp, assume older version we can't read // 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; return;
} }
xmlState = XmlStateFoundGroup; xmlState = XmlStateFoundGroup;
...@@ -354,17 +338,69 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) ...@@ -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) void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{ {
Q_UNUSED(vehicleType) Q_UNUSED(vehicleType)
_loadParameterFactMetaData();
if (_mapParameterName2FactMetaData.contains(fact->name())) { if (_mapParameterName2FactMetaData.contains(fact->name())) {
fact->setMetaData(_mapParameterName2FactMetaData[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;
} }
} }
...@@ -38,19 +38,18 @@ ...@@ -38,19 +38,18 @@
Q_DECLARE_LOGGING_CATEGORY(PX4ParameterMetaDataLog) 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 class PX4ParameterMetaData : public QObject
{ {
Q_OBJECT Q_OBJECT
public: 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 void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
static QString parameterMetaDataFile(void);
private: private:
enum { enum {
...@@ -62,11 +61,10 @@ private: ...@@ -62,11 +61,10 @@ private:
XmlStateDone XmlStateDone
}; };
static void _loadParameterFactMetaData(void); QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
static QMap<QString, FactMetaData*> _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData QMap<QString, FactMetaData*> _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
}; };
#endif #endif
...@@ -74,7 +74,6 @@ ...@@ -74,7 +74,6 @@
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "FirmwarePluginManager.h" #include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "APM/ArduCopterFirmwarePlugin.h" #include "APM/ArduCopterFirmwarePlugin.h"
#include "APM/ArduPlaneFirmwarePlugin.h" #include "APM/ArduPlaneFirmwarePlugin.h"
#include "APM/ArduRoverFirmwarePlugin.h" #include "APM/ArduRoverFirmwarePlugin.h"
...@@ -372,8 +371,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) ...@@ -372,8 +371,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
settings.clear(); settings.clear();
settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION); settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION);
QFile::remove(PX4AirframeLoader::aiframeMetaDataFile()); // Clear parameter cache
QFile::remove(PX4ParameterMetaData::parameterMetaDataFile());
QDir paramDir(ParameterLoader::parameterCacheDir()); QDir paramDir(ParameterLoader::parameterCacheDir());
paramDir.removeRecursively(); paramDir.removeRecursively();
paramDir.mkpath(paramDir.absolutePath()); paramDir.mkpath(paramDir.absolutePath());
......
...@@ -31,6 +31,7 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog") ...@@ -31,6 +31,7 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog") QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog") QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog") QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
QGCLoggingCategoryRegister* _instance = NULL; QGCLoggingCategoryRegister* _instance = NULL;
......
...@@ -35,6 +35,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog) ...@@ -35,6 +35,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog) Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog) Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog) Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
/// @def QGC_LOGGING_CATEGORY /// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a /// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
...@@ -55,6 +55,9 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app) ...@@ -55,6 +55,9 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
_offlineEditingFirmwareTypeMetaData.setEnumInfo(firmwareEnumStrings, firmwareEnumValues); _offlineEditingFirmwareTypeMetaData.setEnumInfo(firmwareEnumStrings, firmwareEnumValues);
_offlineEditingFirmwareTypeFact.setMetaData(&_offlineEditingFirmwareTypeMetaData); _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() QGroundControlQmlGlobal::~QGroundControlQmlGlobal()
......
...@@ -189,7 +189,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -189,7 +189,7 @@ Vehicle::Vehicle(LinkInterface* link,
_missionManager = new MissionManager(this); _missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); 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::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
......
...@@ -641,6 +641,7 @@ private: ...@@ -641,6 +641,7 @@ private:
bool _mapTrajectoryHaveFirstCoordinate; bool _mapTrajectoryHaveFirstCoordinate;
static const int _mapTrajectoryMsecsBetweenPoints = 1000; static const int _mapTrajectoryMsecsBetweenPoints = 1000;
// Toolbox references
FirmwarePluginManager* _firmwarePluginManager; FirmwarePluginManager* _firmwarePluginManager;
AutoPilotPluginManager* _autopilotPluginManager; AutoPilotPluginManager* _autopilotPluginManager;
JoystickManager* _joystickManager; JoystickManager* _joystickManager;
......
...@@ -27,6 +27,11 @@ ...@@ -27,6 +27,11 @@
#include "FirmwareImage.h" #include "FirmwareImage.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "JsonHelper.h"
#include "QGCMAVLink.h"
#include "QGCApplication.h"
#include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include <QDebug> #include <QDebug>
#include <QFile> #include <QFile>
...@@ -37,6 +42,15 @@ ...@@ -37,6 +42,15 @@
#include <QFileInfo> #include <QFileInfo>
#include <QDir> #include <QDir>
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) : FirmwareImage::FirmwareImage(QObject* parent) :
QObject(parent), QObject(parent),
_imageSize(0) _imageSize(0)
...@@ -217,38 +231,52 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) ...@@ -217,38 +231,52 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QJsonObject px4Json = doc.object(); QJsonObject px4Json = doc.object();
// Make sure the keys we need are available // Make sure the keys we need are available
static const char* rgJsonKeys[] = { "board_id", "image_size", "description", "git_identity" }; QString errorString;
for (size_t i=0; i<sizeof(rgJsonKeys)/sizeof(rgJsonKeys[0]); i++) { QStringList requiredKeys;
if (!px4Json.contains(rgJsonKeys[i])) { requiredKeys << _jsonBoardIdKey << _jsonImageKey << _jsonImageSizeKey;
emit errorMessage(QString("Incorrectly formatted firmware file. No %1 key.").arg(rgJsonKeys[i])); if (!JsonHelper::validateRequiredKeys(px4Json, requiredKeys, errorString)) {
return false; emit errorMessage(QString("Firmware file mission required key: %1").arg(errorString));
} return false;
} }
uint32_t firmwareBoardId = (uint32_t)px4Json.value(QString("board_id")).toInt(); // Make sure the keys are the correct type
QStringList keys;
QList<QJsonValue::Type> 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) { if (firmwareBoardId != _boardId) {
emit errorMessage(QString("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardId).arg(_boardId)); emit errorMessage(QString("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardId).arg(_boardId));
return false; 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 // Decompress the parameter xml and save to file
QByteArray decompressedBytes; QByteArray decompressedBytes;
bool success = _decompressJsonValue(px4Json, // JSON object bool success = _decompressJsonValue(px4Json, // JSON object
bytes, // Raw bytes of JSON document bytes, // Raw bytes of JSON document
"parameter_xml_size", // key which holds byte size _jsonParamXmlSizeKey, // key which holds byte size
"parameter_xml", // key which holds compress bytes _jsonParamXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes decompressedBytes); // Returned decompressed bytes
if (success) { 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; QSettings settings;
QDir parameterDir = QFileInfo(settings.fileName()).dir(); QDir parameterDir = QFileInfo(settings.fileName()).dir();
QString parameterFilename = parameterDir.filePath("PX4ParameterFactMetaData.xml"); QString parameterFilename = parameterDir.filePath("ParameterFactMetaData.xml");
QFile parameterFile(parameterFilename); QFile parameterFile(parameterFilename);
if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) { if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
qint64 bytesWritten = parameterFile.write(decompressedBytes); qint64 bytesWritten = parameterFile.write(decompressedBytes);
if (bytesWritten != decompressedBytes.count()) { if (bytesWritten != decompressedBytes.count()) {
// FIXME: What about these warnings?
emit statusMessage(QString("Write failed for parameter meta data file, error: %1").arg(parameterFile.errorString())); emit statusMessage(QString("Write failed for parameter meta data file, error: %1").arg(parameterFile.errorString()));
parameterFile.close(); parameterFile.close();
QFile::remove(parameterFilename); QFile::remove(parameterFilename);
...@@ -258,14 +286,17 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) ...@@ -258,14 +286,17 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
} else { } else {
emit statusMessage(QString("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename).arg(parameterFile.errorString())); 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 // Decompress the airframe xml and save to file
success = _decompressJsonValue(px4Json, // JSON object success = _decompressJsonValue(px4Json, // JSON object
bytes, // Raw bytes of JSON document bytes, // Raw bytes of JSON document
"airframe_xml_size", // key which holds byte size _jsonAirframeXmlSizeKey, // key which holds byte size
"airframe_xml", // key which holds compress bytes _jsonAirframeXmlKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes decompressedBytes); // Returned decompressed bytes
if (success) { if (success) {
// We cache the airframe xml in the same location as settings and parameters // We cache the airframe xml in the same location as settings and parameters
QSettings settings; QSettings settings;
...@@ -293,8 +324,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) ...@@ -293,8 +324,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
_imageSize = px4Json.value(QString("image_size")).toInt(); _imageSize = px4Json.value(QString("image_size")).toInt();
success = _decompressJsonValue(px4Json, // JSON object success = _decompressJsonValue(px4Json, // JSON object
bytes, // Raw bytes of JSON document bytes, // Raw bytes of JSON document
"image_size", // key which holds byte size _jsonImageSizeKey, // key which holds byte size
"image", // key which holds compress bytes _jsonImageKey, // key which holds compressed bytes
decompressedBytes); // Returned decompressed bytes decompressedBytes); // Returned decompressed bytes
if (!success) { if (!success) {
return false; return false;
...@@ -341,7 +372,7 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J ...@@ -341,7 +372,7 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
} }
int decompressedSize = jsonObject.value(QString(sizeKey)).toInt(); int decompressedSize = jsonObject.value(QString(sizeKey)).toInt();
if (decompressedSize == 0) { 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; return false;
} }
...@@ -353,12 +384,12 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J ...@@ -353,12 +384,12 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
QStringList parts = QString(jsonDocBytes).split(QString("\"%1\": \"").arg(bytesKey)); QStringList parts = QString(jsonDocBytes).split(QString("\"%1\": \"").arg(bytesKey));
if (parts.count() == 1) { 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; return false;
} }
parts = parts.last().split("\""); parts = parts.last().split("\"");
if (parts.count() == 1) { 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; return false;
} }
...@@ -374,11 +405,11 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J ...@@ -374,11 +405,11 @@ bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< J
decompressedBytes = qUncompress(raw); decompressedBytes = qUncompress(raw);
if (decompressedBytes.count() == 0) { 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; return false;
} }
if (decompressedBytes.count() != decompressedSize) { 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; return false;
} }
......
...@@ -98,6 +98,15 @@ private: ...@@ -98,6 +98,15 @@ private:
QString _binFilename; QString _binFilename;
QList<IntelHexBlock_t> _ihxBlocks; QList<IntelHexBlock_t> _ihxBlocks;
uint32_t _imageSize; 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 #endif
...@@ -508,6 +508,7 @@ ...@@ -508,6 +508,7 @@
1 50 SYS_AUTOCONFIG 0 6 1 50 SYS_AUTOCONFIG 0 6
1 50 SYS_AUTOSTART 10016 6 1 50 SYS_AUTOSTART 10016 6
1 50 SYS_COMPANION 157600 6 1 50 SYS_COMPANION 157600 6
1 50 SYS_PARAM_VER 1 6
1 50 SYS_RESTART_TYPE 0 6 1 50 SYS_RESTART_TYPE 0 6
1 50 SYS_USE_IO 1 6 1 50 SYS_USE_IO 1 6
1 50 TEST_D 0.01 9 1 50 TEST_D 0.01 9
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment