Commit bf6599e4 authored by Don Gagne's avatar Don Gagne

Versioned parameter meta data cache

parent 8d0b28f0
......@@ -231,13 +231,15 @@
</qresource>
<qresource prefix="/AutoPilotPlugins/PX4">
<file alias="AirframeFactMetaData.xml">src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml</file>
<file alias="ParameterFactMetaData.xml">src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml</file>
</qresource>
<qresource prefix="/AutoPilotPlugins/APM">
<file alias="APMAirframeFactMetaData.xml">src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml</file>
</qresource>
<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 prefix="/opengl">
<file>resources/opengl/buglist.json</file>
......
......@@ -606,7 +606,6 @@ HEADERS+= \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
src/Vehicle/MultiVehicleManager.h \
......@@ -661,8 +660,8 @@ SOURCES += \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
src/Vehicle/MultiVehicleManager.cc \
......
......@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "GenericAutoPilotPlugin.h"
#include "FirmwarePlugin/Generic/GenericFirmwarePlugin.h" // FIXME: Hack
GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
AutoPilotPlugin(vehicle, parent)
......
<?xml version='1.0' encoding='UTF-8'?>
<airframes>
<version>1</version>
<airframe_version_minor>1</airframe_version_minor>
<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)">
<maintainer>Emmanuel Roussel</maintainer>
......@@ -230,6 +231,13 @@
<maintainer>Blankered</maintainer>
<type>Quadrotor x</type>
</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 image="Rover" name="Rover">
<airframe id="50001" maintainer="John Doe &lt;john@example.com&gt;" name="Axial Racing AX10">
......
......@@ -134,6 +134,10 @@ void PX4AirframeLoader::loadAirframeMetaData(void)
return;
}
} else if (elementName == "airframe_version_major") {
// Just skip over for now
} else if (elementName == "airframe_version_minor") {
// Just skip over for now
} else if (elementName == "airframe_group") {
if (xmlState != XmlStateFoundVersion) {
......
This diff is collapsed.
......@@ -40,7 +40,6 @@
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog)
/// Connects to Parameter Manager to load/update Facts
......@@ -50,7 +49,7 @@ class ParameterLoader : public QObject
public:
/// @param uas Uas which this set of facts is associated with
ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
ParameterLoader(Vehicle* vehicle);
~ParameterLoader();
......@@ -91,6 +90,19 @@ public:
QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream);
/// Returns the version number for the parameter set, -1 if not known
int parameterSetVersion(void) { return _parameterSetMajorVersion; }
/// Returns the newest available parameter meta data file (from cache or internal) for the specified information.
/// @param wantedMajorVersion Major version you are looking for
/// @param[out] majorVersion Major version for found meta data
/// @param[out] minorVersion Minor version for found meta data
/// @return Meta data file name of best match, emptyString is none found
static QString parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion);
/// If this file is newer than anything in the cache, cache it as the latest version
static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
signals:
/// Signalled when the full set of facts are ready
......@@ -103,7 +115,6 @@ signals:
void restartWaitingParamTimer(void);
protected:
AutoPilotPlugin* _autopilot;
Vehicle* _vehicle;
MAVLinkProtocol* _mavlink;
......@@ -123,6 +134,7 @@ private:
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int uasId, int componentId);
void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value);
void _addMetaDataToAll(void);
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
......@@ -134,18 +146,22 @@ private:
/// First mapping is by component id
/// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant;
QMap<int, QMap<int, QString> > _mapParameterId2Name;
/// First mapping is by component id
/// Second mapping is group name, to Fact
QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName;
bool _parametersReady; ///< true: full set of parameters correctly loaded
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
bool _saveRequired; ///< true: _saveToEEPROM should be called
int _defaultComponentId;
QString _defaultComponentIdParam;
bool _parametersReady; ///< true: full set of parameters correctly loaded
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether succesful or not
bool _saveRequired; ///< true: _saveToEEPROM should be called
int _defaultComponentId;
QString _defaultComponentIdParam; ///< Parameter which identifies default component
QString _versionParam; ///< Parameter which contains parameter set version
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
static const int _maxInitialLoadRetry = 10; ///< Maximum a retries on initial index based load
QMap<int, int> _paramCountMap; ///< Key: Component id, Value: count of parameters in this component
......@@ -162,6 +178,8 @@ private:
QMutex _dataMutex;
static Fact _defaultFact; ///< Used to return default fact, when parameter not found
static const char* _cachedMetaDataFilePrefix;
};
#endif
......@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "APMFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h"
#include "QGCApplication.h"
......@@ -473,11 +472,16 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return true;
}
void APMFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
void APMFirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
{
_parameterMetaData.addMetaDataToFact(fact, vehicleType);
}
APMParameterMetaData* apmMetaData = qobject_cast<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)
{
......@@ -508,3 +512,11 @@ void APMFirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QSt
fixedWingJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoFixedWing.json");
multiRotorJsonFilename = QStringLiteral(":/json/APM/MavCmdInfoMultiRotor.json");
}
QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
Q_UNUSED(metaDataFile);
APMParameterMetaData* metaData = new APMParameterMetaData;
return metaData;
}
......@@ -80,19 +80,25 @@ class APMFirmwarePlugin : public FirmwarePlugin
public:
// Overrides from FirmwarePlugin
virtual bool isCapable(FirmwareCapabilities capabilities);
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
virtual QStringList flightModes(void);
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QList<MAV_CMD> supportedMissionCommands(void) final;
bool isCapable(FirmwareCapabilities capabilities) final;
QStringList flightModes(void) final;
QString flightMode(uint8_t base_mode, uint32_t custom_mode) final;
bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
int manualControlReservedButtonCount(void) final;
void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
void initializeVehicle(Vehicle* vehicle) final;
bool sendHomePositionToVehicle(void) final;
void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam(void) const final { return QString("SYSID_SW_TYPE"); }
void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const final;
QString getVersionParam(void) final { return QStringLiteral("SYSID_SW_MREV"); }
QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/APM/APMParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
protected:
/// All access to singleton is through stack specific implementation
......@@ -109,7 +115,6 @@ private:
APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded;
QList<APMCustomMode> _supportedModes;
APMParameterMetaData _parameterMetaData;
};
#endif
......@@ -21,9 +21,6 @@
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "APMParameterMetaData.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
......@@ -34,15 +31,13 @@
#include <QDebug>
#include <QStack>
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
bool APMParameterMetaData::_parameterMetaDataLoaded = false;
QMap<QString, ParameterNametoFactMetaDataMap> APMParameterMetaData::_vehicleTypeToParametersMap;
QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
QGC_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog, "APMParameterMetaDataVerboseLog")
APMParameterMetaData::APMParameterMetaData(QObject* parent) :
QObject(parent)
APMParameterMetaData::APMParameterMetaData(void)
: _parameterMetaDataLoaded(false)
{
// APM meta data is not yet versioned
_loadParameterFactMetaData();
}
......@@ -146,7 +141,7 @@ void APMParameterMetaData::_loadParameterFactMetaData()
// Fixme:: always picking up the bundled xml, we would like to update it from web
// just not sure right now as the xml is in bad shape.
if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) {
parameterFilename = ":/FirmwarePlugin/APM/apm.pdef.xml";
parameterFilename = ":/FirmwarePlugin/APM/APMParameterFactMetaData.xml";
}
qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename;
......@@ -428,11 +423,8 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa
return true;
}
/// Override from FactLoad which connects the meta data to the fact
void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{
_loadParameterFactMetaData();
const QString mavTypeString = mavTypeToString(vehicleType);
APMFactMetaDataRaw* rawMetaData = NULL;
......@@ -591,3 +583,12 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
// FixMe:: not handling increment size as their is no place for it in FactMetaData and no ui
fact->setMetaData(metaData);
}
void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
Q_UNUSED(metaDataFile);
// Versioning not yet supported
majorVersion = -1;
minorVersion = -1;
}
......@@ -34,6 +34,9 @@
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataVerboseLog)
class APMFactMetaDataRaw
{
public:
......@@ -54,11 +57,6 @@ public:
QList<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
......@@ -69,15 +67,11 @@ class APMParameterMetaData : public QObject
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
APMParameterMetaData(QObject* parent = NULL);
APMParameterMetaData(void);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
// Overrides from ParameterLoader
static void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
static void addMetaDataToFacts(QVariantMap &facts, MAV_TYPE vehicleType);
void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);
static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
private:
enum {
......@@ -90,18 +84,17 @@ private:
XmlStateFoundGroup,
XmlStateFoundParameter,
XmlStateDone
};
};
static void _loadParameterFactMetaData();
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
static bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
static bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
static void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap<QString,QStringList>& groupMembers);
static QString mavTypeToString(MAV_TYPE vehicleTypeEnum);
void _loadParameterFactMetaData();
QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk);
bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName);
bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData);
void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap<QString,QStringList>& groupMembers);
QString mavTypeToString(MAV_TYPE vehicleTypeEnum);
static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
static QMap<QString, ParameterNametoFactMetaDataMap> _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map>
bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
QMap<QString, ParameterNametoFactMetaDataMap> _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map>
};
#endif
......@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "ArduCopterFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode(mode, settable)
......
......@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduPlaneFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
......
......@@ -25,7 +25,6 @@
/// @author Pritam Ghanghas <pritam.ghanghas@gmail.com>
#include "ArduRoverFirmwarePlugin.h"
#include "Generic/GenericFirmwarePlugin.h"
APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
: APMCustomMode(mode, settable)
......
......@@ -21,22 +21,18 @@
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h" // FIXME: Hack
#include "FirmwarePlugin.h"
#include <QDebug>
QList<VehicleComponent*> GenericFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
QList<VehicleComponent*> FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
Q_UNUSED(vehicle);
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;
......@@ -72,25 +68,25 @@ QString GenericFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mod
return flightMode;
}
bool GenericFirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
bool FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
Q_UNUSED(flightMode);
Q_UNUSED(base_mode);
Q_UNUSED(custom_mode);
qWarning() << "GenericFirmwarePlugin::setFlightMode called on base class, not supported";
qWarning() << "FirmwarePlugin::setFlightMode called on base class, not supported";
return false;
}
int GenericFirmwarePlugin::manualControlReservedButtonCount(void)
int FirmwarePlugin::manualControlReservedButtonCount(void)
{
// We don't know whether the firmware is going to used any of these buttons.
// So reserve them all.
return -1;
}
void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
void FirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
Q_UNUSED(message);
......@@ -98,14 +94,14 @@ void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_messa
// Generic plugin does no message adjustment
}
void GenericFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
void FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
// Generic Flight Stack is by definition "generic", so no extra work
}
bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
bool FirmwarePlugin::sendHomePositionToVehicle(void)
{
// Generic stack does not want home position sent in the first position.
// Subsequent sequence numbers must be adjusted.
......@@ -113,25 +109,23 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return false;
}
void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{
Q_UNUSED(vehicleType)
// Add default meta data
FactMetaData* metaData = new FactMetaData(fact->type(), fact);
fact->setMetaData(metaData);
}
QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
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
commonJsonFilename.clear();
fixedWingJsonFilename.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;
/// This is the base class for Firmware specific plugins
///
/// The FirmwarePlugin class is the abstract base class which represents the methods and objects
/// which are specific to a certain Firmware flight stack. This is the only place where
/// flight stack specific code should reside in QGroundControl. The remainder of the
/// QGroundControl source is generic to a common mavlink implementation. The implementation
/// in the base class supports mavlink generic firmware. Override the base clase virtuals
/// to create you firmware specific plugin.
/// The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack.
/// This is the only place where flight stack specific code should reside in QGroundControl. The remainder of the
/// QGroundControl source is generic to a common mavlink implementation. The implementation in the base class supports
/// mavlink generic firmware. Override the base clase virtuals to create your own firmware specific plugin.
class FirmwarePlugin : public QObject
{
......@@ -53,31 +51,30 @@ public:
/// Set of optional capabilites which firmware may support
typedef enum {
SetFlightModeCapability, ///< FirmwarePlugin::setFlightMode method is supported
MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
MavCmdPreflightStorageCapability, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
} FirmwareCapabilities;
/// @return true: Firmware supports all specified capabilites
virtual bool isCapable(FirmwareCapabilities capabilities) = 0;
virtual bool isCapable(FirmwareCapabilities capabilities) { Q_UNUSED(capabilities); return false; }
/// Returns VehicleComponents for specified Vehicle
/// @param vehicle Vehicle to associate with components
/// @return List of VehicleComponents for the specified vehicle. Caller owns returned objects and must
/// free when no longer needed.
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) = 0;
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
/// Returns the list of available flight modes
virtual QStringList flightModes(void) = 0;
virtual QStringList flightModes(void) { return QStringList(); }
/// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable.
/// @param base_mode Base mode from mavlink HEARTBEAT message
/// @param custom_mode Custom mode from mavlink HEARTBEAT message
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) = 0;
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode);
/// Sets base_mode and custom_mode to specified flight mode.
/// @param[out] base_mode Base mode for SET_MODE mavlink message
/// @param[out] custom_mode Custom mode for SET_MODE mavlink message
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) = 0;
virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
/// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific
/// not just this. I'm going to try to change that. If not, this will need to be removed.
......@@ -85,17 +82,17 @@ public:
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
/// The remainder can be assigned to Vehicle actions.
/// @return -1: reserver all buttons, >0 number of buttons to reserve
virtual int manualControlReservedButtonCount(void) = 0;
virtual int manualControlReservedButtonCount(void);
/// Called before any mavlink message is processed by Vehicle such that the firmwre plugin
/// can adjust any message characteristics. This is handy to adjust or differences in mavlink
/// spec implementations such that the base code can remain mavlink generic.
/// @param vehicle Vehicle message came from
/// @param message[in,out] Mavlink message to adjust if needed.
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) = 0;
virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
/// Called when Vehicle is first created to send any necessary mavlink messages to the firmware.
virtual void initializeVehicle(Vehicle* vehicle) = 0;
virtual void initializeVehicle(Vehicle* vehicle);
/// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position.
......@@ -103,22 +100,38 @@ public:
/// true: Send first mission item as home position to vehicle. When vehicle has no mission items on
/// it, it may or may not return a home position back in position 0.
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void) = 0;
virtual bool sendHomePositionToVehicle(void);
/// Returns the parameter that is used to identify the default component
virtual QString getDefaultComponentIdParam(void) const = 0;
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
/// Returns the parameter which is used to identify the version number of parameter set
virtual QString getVersionParam(void) { return QString(); }
/// Returns the parameter set version info pulled from inside the meta data file. -1 if not found.
virtual void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
/// Returns the internal resource parameter meta date file.
virtual QString internalParameterMetaDataFile(void) { return QString(); }
/// Loads the specified parameter meta data file.
/// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is reponsible to
/// call deleteParameterMetaData when no longer needed.
virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; }
/// Adds the parameter meta data to the Fact
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) = 0;
/// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; }
/// List of supported mission commands. Empty list for all commands supported.
virtual QList<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.
/// @param[out] commonJsonFilename Filename for common overrides
/// @param[out] fixedWingJsonFilename Filename for fixed wing overrides
/// @param[out] multiRotorJsonFilename Filename for multi rotor overrides
virtual void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const = 0;
virtual void missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const;
};
#endif
......@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "FirmwarePluginManager.h"
#include "Generic/GenericFirmwarePlugin.h"
#include "APM/ArduCopterFirmwarePlugin.h"
#include "APM/ArduPlaneFirmwarePlugin.h"
#include "APM/ArduRoverFirmwarePlugin.h"
......@@ -91,7 +90,12 @@ FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT
}
if (!_genericFirmwarePlugin) {
_genericFirmwarePlugin = new GenericFirmwarePlugin;
_genericFirmwarePlugin = new FirmwarePlugin;
}
return _genericFirmwarePlugin;
}
void FirmwarePluginManager::clearSettings(void)
{
// FIXME: NYI
}
......@@ -38,7 +38,6 @@ class ArduCopterFirmwarePlugin;
class ArduPlaneFirmwarePlugin;
class ArduRoverFirmwarePlugin;
class PX4FirmwarePlugin;
class GenericFirmwarePlugin;
/// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type.
......@@ -56,11 +55,14 @@ public:
/// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT.
FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType);
/// Clears settings from all firmware plugins.
void clearSettings(void);
private:
ArduCopterFirmwarePlugin* _arduCopterFirmwarePlugin;
ArduPlaneFirmwarePlugin* _arduPlaneFirmwarePlugin;
ArduRoverFirmwarePlugin* _arduRoverFirmwarePlugin;
GenericFirmwarePlugin* _genericFirmwarePlugin;
FirmwarePlugin* _genericFirmwarePlugin;
PX4FirmwarePlugin* _px4FirmwarePlugin;
};
......
/*=====================================================================
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