Commit f132b110 authored by Don Gagne's avatar Don Gagne

ParameterLoader to Vehicle, ParameterMetaData to FirmwarePlugin

parent 8b0b8906
...@@ -527,14 +527,13 @@ HEADERS+= \ ...@@ -527,14 +527,13 @@ HEADERS+= \
src/FirmwarePlugin/FirmwarePluginManager.h \ src/FirmwarePlugin/FirmwarePluginManager.h \
src/FirmwarePlugin/FirmwarePlugin.h \ src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/APM/APMFirmwarePlugin.h \ src/FirmwarePlugin/APM/APMFirmwarePlugin.h \
src/FirmwarePlugin/APM/APMParameterLoader.h \ src/FirmwarePlugin/APM/APMParameterMetaData.h \
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/Generic/GenericFirmwarePlugin.h \
src/FirmwarePlugin/Generic/GenericParameterLoader.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4ParameterLoader.h \ src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
src/Vehicle/MultiVehicleManager.h \ src/Vehicle/MultiVehicleManager.h \
src/Vehicle/Vehicle.h \ src/Vehicle/Vehicle.h \
src/VehicleSetup/VehicleComponent.h \ src/VehicleSetup/VehicleComponent.h \
...@@ -568,15 +567,14 @@ SOURCES += \ ...@@ -568,15 +567,14 @@ SOURCES += \
src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \ src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \
src/FirmwarePlugin/APM/APMParameterLoader.cc \ src/FirmwarePlugin/APM/APMParameterMetaData.cc \
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/FirmwarePluginManager.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \
src/FirmwarePlugin/Generic/GenericParameterLoader.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4ParameterLoader.cc \ src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/Vehicle.cc \ src/Vehicle/Vehicle.cc \
src/VehicleSetup/VehicleComponent.cc \ src/VehicleSetup/VehicleComponent.cc \
......
...@@ -25,7 +25,7 @@ ...@@ -25,7 +25,7 @@
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "UAS.h" #include "UAS.h"
#include "FirmwarePlugin/APM/APMParameterLoader.h" // FIXME: Hack #include "FirmwarePlugin/APM/APMParameterMetaData.h" // FIXME: Hack
#include "FirmwarePlugin/APM/APMFirmwarePlugin.h" // FIXME: Hack #include "FirmwarePlugin/APM/APMFirmwarePlugin.h" // FIXME: Hack
/// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type. /// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type.
...@@ -34,9 +34,6 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : ...@@ -34,9 +34,6 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
_incorrectParameterVersion(false) _incorrectParameterVersion(false)
{ {
Q_ASSERT(vehicle); Q_ASSERT(vehicle);
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
} }
APMAutoPilotPlugin::~APMAutoPilotPlugin() APMAutoPilotPlugin::~APMAutoPilotPlugin()
...@@ -44,11 +41,6 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin() ...@@ -44,11 +41,6 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin()
} }
void APMAutoPilotPlugin::clearStaticData(void)
{
APMParameterLoader::clearStaticData();
}
const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
{ {
static const QVariantList emptyList; static const QVariantList emptyList;
......
...@@ -39,8 +39,6 @@ public: ...@@ -39,8 +39,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
static void clearStaticData(void);
public slots: public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters); void _parametersReadyPreChecks(bool missingParameters);
......
...@@ -109,34 +109,34 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void) ...@@ -109,34 +109,34 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
void AutoPilotPlugin::refreshAllParameters(void) void AutoPilotPlugin::refreshAllParameters(void)
{ {
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshAllParameters(); _vehicle->getParameterLoader()->refreshAllParameters();
} }
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name) void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{ {
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParameter(componentId, name); _vehicle->getParameterLoader()->refreshParameter(componentId, name);
} }
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix) void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
{ {
_firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParametersPrefix(componentId, namePrefix); _vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix);
} }
bool AutoPilotPlugin::parameterExists(int componentId, const QString& name) bool AutoPilotPlugin::parameterExists(int componentId, const QString& name)
{ {
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); return _vehicle->getParameterLoader()->parameterExists(componentId, name);
} }
Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name) Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name)
{ {
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); return _vehicle->getParameterLoader()->getFact(componentId, name);
} }
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{ {
switch (provider) { switch (provider) {
case FactSystem::ParameterProvider: case FactSystem::ParameterProvider:
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); return _vehicle->getParameterLoader()->parameterExists(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -149,7 +149,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -149,7 +149,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
{ {
switch (provider) { switch (provider) {
case FactSystem::ParameterProvider: case FactSystem::ParameterProvider:
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); return _vehicle->getParameterLoader()->getFact(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -160,20 +160,20 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -160,20 +160,20 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
QStringList AutoPilotPlugin::parameterNames(int componentId) QStringList AutoPilotPlugin::parameterNames(int componentId)
{ {
return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterNames(componentId); return _vehicle->getParameterLoader()->parameterNames(componentId);
} }
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void) const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{ {
return _firmwarePlugin->getParameterLoader(this, _vehicle)->getGroupMap(); return _vehicle->getParameterLoader()->getGroupMap();
} }
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{ {
_firmwarePlugin->getParameterLoader(this, _vehicle)->writeParametersToStream(stream, _vehicle->uas()->getUASName()); _vehicle->getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName());
} }
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{ {
return _firmwarePlugin->getParameterLoader(this, _vehicle)->readParametersFromStream(stream); return _vehicle->getParameterLoader()->readParametersFromStream(stream);
} }
...@@ -114,8 +114,6 @@ public: ...@@ -114,8 +114,6 @@ public:
// Must be implemented by derived class // Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0; virtual const QVariantList& vehicleComponents(void) = 0;
static void clearStaticData(void);
// Property accessors // Property accessors
bool parametersReady(void) { return _parametersReady; } bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; } bool missingParameters(void) { return _missingParameters; }
......
...@@ -37,12 +37,6 @@ AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) : ...@@ -37,12 +37,6 @@ AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) :
} }
AutoPilotPluginManager::~AutoPilotPluginManager()
{
PX4AutoPilotPlugin::clearStaticData();
GenericAutoPilotPlugin::clearStaticData();
}
AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle) AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle)
{ {
switch (vehicle->firmwareType()) { switch (vehicle->firmwareType()) {
......
...@@ -49,7 +49,6 @@ public: ...@@ -49,7 +49,6 @@ public:
private: private:
/// All access to singleton is through AutoPilotPluginManager::instance /// All access to singleton is through AutoPilotPluginManager::instance
AutoPilotPluginManager(QObject* parent = NULL); AutoPilotPluginManager(QObject* parent = NULL);
~AutoPilotPluginManager();
}; };
#endif #endif
...@@ -31,14 +31,6 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent ...@@ -31,14 +31,6 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent
AutoPilotPlugin(vehicle, parent) AutoPilotPlugin(vehicle, parent)
{ {
Q_ASSERT(vehicle); Q_ASSERT(vehicle);
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
}
void GenericAutoPilotPlugin::clearStaticData(void)
{
// No Static data yet
} }
const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void)
......
...@@ -40,8 +40,6 @@ public: ...@@ -40,8 +40,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
static void clearStaticData(void);
public slots: public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
......
...@@ -190,9 +190,3 @@ void PX4AirframeLoader::loadAirframeFactMetaData(void) ...@@ -190,9 +190,3 @@ void PX4AirframeLoader::loadAirframeFactMetaData(void)
_airframeMetaDataLoaded = true; _airframeMetaDataLoaded = true;
} }
void PX4AirframeLoader::clearStaticData(void)
{
AirframeComponentAirframes::clear();
_airframeMetaDataLoaded = false;
}
...@@ -50,7 +50,6 @@ public: ...@@ -50,7 +50,6 @@ public:
PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL); PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL);
static void loadAirframeFactMetaData(void); static void loadAirframeFactMetaData(void);
static void clearStaticData(void);
private: private:
enum { enum {
......
...@@ -28,7 +28,7 @@ ...@@ -28,7 +28,7 @@
#include "AirframeComponentController.h" #include "AirframeComponentController.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "UAS.h" #include "UAS.h"
#include "FirmwarePlugin/PX4/PX4ParameterLoader.h" // FIXME: Hack #include "FirmwarePlugin/PX4/PX4ParameterMetaData.h" // FIXME: Hack
#include "FirmwarePlugin/PX4/PX4FirmwarePlugin.h" // FIXME: Hack #include "FirmwarePlugin/PX4/PX4FirmwarePlugin.h" // FIXME: Hack
/// @file /// @file
...@@ -81,9 +81,6 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : ...@@ -81,9 +81,6 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) :
Q_CHECK_PTR(_airframeFacts); Q_CHECK_PTR(_airframeFacts);
PX4AirframeLoader::loadAirframeFactMetaData(); PX4AirframeLoader::loadAirframeFactMetaData();
// This kicks off parameter load
_firmwarePlugin->getParameterLoader(this, vehicle);
} }
PX4AutoPilotPlugin::~PX4AutoPilotPlugin() PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
...@@ -91,12 +88,6 @@ PX4AutoPilotPlugin::~PX4AutoPilotPlugin() ...@@ -91,12 +88,6 @@ PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
delete _airframeFacts; delete _airframeFacts;
} }
void PX4AutoPilotPlugin::clearStaticData(void)
{
PX4ParameterLoader::clearStaticData();
PX4AirframeLoader::clearStaticData();
}
const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
{ {
if (_components.count() == 0 && !_incorrectParameterVersion) { if (_components.count() == 0 && !_incorrectParameterVersion) {
......
...@@ -51,8 +51,6 @@ public: ...@@ -51,8 +51,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
static void clearStaticData(void);
// These methods should only be used by objects within the plugin // These methods should only be used by objects within the plugin
AirframeComponent* airframeComponent(void) { return _airframeComponent; } AirframeComponent* airframeComponent(void) { return _airframeComponent; }
RadioComponent* radioComponent(void) { return _radioComponent; } RadioComponent* radioComponent(void) { return _radioComponent; }
......
...@@ -37,7 +37,7 @@ ...@@ -37,7 +37,7 @@
/// additional meta data associated with a Fact such as description, min/max ranges and so forth. /// additional meta data associated with a Fact such as description, min/max ranges and so forth.
/// The FactValidator object is a QML validator which validates input according to the FactMetaData /// The FactValidator object is a QML validator which validates input according to the FactMetaData
/// settings. Client code can then use this system to expose sets of Facts to QML code. An example /// settings. Client code can then use this system to expose sets of Facts to QML code. An example
/// of this is the PX4ParameterLoader onbject which is part of the PX4 AutoPilot plugin. It exposes /// of this is the PX4ParameterMetaData onbject which is part of the PX4 AutoPilot plugin. It exposes
/// the firmware parameters to QML such that you can bind QML ui elements directly to parameters. /// the firmware parameters to QML such that you can bind QML ui elements directly to parameters.
class FactSystem : public QGCSingleton class FactSystem : public QGCSingleton
......
...@@ -198,7 +198,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param ...@@ -198,7 +198,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
// Attempt to determine default component id // Attempt to determine default component id
if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) { if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) {
_defaultComponentIdParam = getDefaultComponentIdParam(); _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam();
} }
if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) { if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
_defaultComponentId = componentId; _defaultComponentId = componentId;
...@@ -255,7 +255,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param ...@@ -255,7 +255,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
fact->_containerSetValue(value); fact->_containerSetValue(value);
if (setMetaData) { if (setMetaData) {
_addMetaDataToFact(fact); _vehicle->firmwarePlugin()->addMetaDataToFact(fact);
} }
_dataMutex.unlock(); _dataMutex.unlock();
...@@ -293,12 +293,6 @@ void ParameterLoader::_valueUpdated(const QVariant& value) ...@@ -293,12 +293,6 @@ void ParameterLoader::_valueUpdated(const QVariant& value)
qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")"; qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
} }
void ParameterLoader::_addMetaDataToFact(Fact* fact)
{
FactMetaData* metaData = new FactMetaData(fact->type(), this);
fact->setMetaData(metaData);
}
void ParameterLoader::refreshAllParameters(void) void ParameterLoader::refreshAllParameters(void)
{ {
_dataMutex.lock(); _dataMutex.lock();
......
...@@ -86,10 +86,6 @@ public: ...@@ -86,10 +86,6 @@ public:
QString readParametersFromStream(QTextStream& stream); QString readParametersFromStream(QTextStream& stream);
void writeParametersToStream(QTextStream &stream, const QString& name); void writeParametersToStream(QTextStream &stream, const QString& name);
/// Return the parameter for which the default component id is derived from. Return an empty
/// string is this is not available.
virtual QString getDefaultComponentIdParam(void) const = 0;
signals: signals:
/// Signalled when the full set of facts are ready /// Signalled when the full set of facts are ready
...@@ -102,10 +98,6 @@ signals: ...@@ -102,10 +98,6 @@ signals:
void restartWaitingParamTimer(void); void restartWaitingParamTimer(void);
protected: protected:
/// Base implementation adds generic meta data based on variant type. Derived class can override to provide
/// more details meta data.
virtual void _addMetaDataToFact(Fact* fact);
AutoPilotPlugin* _autopilot; AutoPilotPlugin* _autopilot;
Vehicle* _vehicle; Vehicle* _vehicle;
MAVLinkProtocol* _mavlink; MAVLinkProtocol* _mavlink;
......
...@@ -141,7 +141,6 @@ QString APMCustomMode::modeString() const ...@@ -141,7 +141,6 @@ QString APMCustomMode::modeString() const
APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent) : FirmwarePlugin(parent)
, _parameterLoader(NULL)
{ {
_textSeverityAdjustmentNeeded = false; _textSeverityAdjustmentNeeded = false;
} }
...@@ -387,18 +386,7 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -387,18 +386,7 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
return true; return true;
} }
ParameterLoader* APMFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) void APMFirmwarePlugin::addMetaDataToFact(Fact* fact)
{ {
if (!_parameterLoader) { _parameterMetaData.addMetaDataToFact(fact);
_parameterLoader = new APMParameterLoader(autopilotPlugin, vehicle, this);
Q_CHECK_PTR(_parameterLoader);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &APMParameterLoader::parameterListProgress, autopilotPlugin, &APMAutoPilotPlugin::parameterListProgress);
_parameterLoader->loadParameterFactMetaData();
}
return _parameterLoader;
} }
...@@ -29,7 +29,7 @@ ...@@ -29,7 +29,7 @@
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "APMParameterLoader.h" #include "APMParameterMetaData.h"
Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog) Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog)
...@@ -89,7 +89,8 @@ public: ...@@ -89,7 +89,8 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle); virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
protected: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation
...@@ -103,7 +104,7 @@ private: ...@@ -103,7 +104,7 @@ private:
APMFirmwareVersion _firmwareVersion; APMFirmwareVersion _firmwareVersion;
bool _textSeverityAdjustmentNeeded; bool _textSeverityAdjustmentNeeded;
QList<APMCustomMode> _supportedModes; QList<APMCustomMode> _supportedModes;
APMParameterLoader* _parameterLoader; APMParameterMetaData _parameterMetaData;
}; };
#endif #endif
...@@ -24,7 +24,7 @@ ...@@ -24,7 +24,7 @@
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "APMParameterLoader.h" #include "APMParameterMetaData.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
...@@ -33,15 +33,15 @@ ...@@ -33,15 +33,15 @@
#include <QDir> #include <QDir>
#include <QDebug> #include <QDebug>
QGC_LOGGING_CATEGORY(APMParameterLoaderLog, "APMParameterLoaderLog") QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog")
bool APMParameterLoader::_parameterMetaDataLoaded = false; bool APMParameterMetaData::_parameterMetaDataLoaded = false;
QMap<QString, FactMetaData*> APMParameterLoader::_mapParameterName2FactMetaData; QMap<QString, FactMetaData*> APMParameterMetaData::_mapParameterName2FactMetaData;
APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : APMParameterMetaData::APMParameterMetaData(QObject* parent) :
ParameterLoader(autopilot, vehicle, parent) QObject(parent)
{ {
Q_ASSERT(vehicle); _loadParameterFactMetaData();
} }
/// Converts a string to a typed QVariant /// Converts a string to a typed QVariant
...@@ -49,7 +49,7 @@ APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehi ...@@ -49,7 +49,7 @@ APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehi
/// @param type Type for Fact which dictates the QVariant type as well /// @param type Type for Fact which dictates the QVariant type as well
/// @param convertOk Returned: true: conversion success, false: conversion failure /// @param convertOk Returned: true: conversion success, false: conversion failure
/// @return Returns the correctly type QVariant /// @return Returns the correctly type QVariant
QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk)
{ {
QVariant var(string); QVariant var(string);
...@@ -81,7 +81,7 @@ QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMe ...@@ -81,7 +81,7 @@ QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMe
/// Load Parameter Fact meta data /// Load Parameter Fact meta data
/// ///
/// The meta data comes from firmware parameters.xml file. /// The meta data comes from firmware parameters.xml file.
void APMParameterLoader::loadParameterFactMetaData(void) void APMParameterMetaData::_loadParameterFactMetaData(void)
{ {
if (_parameterMetaDataLoaded) { if (_parameterMetaDataLoaded) {
return; return;
...@@ -94,20 +94,11 @@ void APMParameterLoader::loadParameterFactMetaData(void) ...@@ -94,20 +94,11 @@ void APMParameterLoader::loadParameterFactMetaData(void)
// has multiple sets of static meta data // has multiple sets of static meta data
} }
void APMParameterLoader::clearStaticData(void)
{
foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) {
delete _mapParameterName2FactMetaData[parameterName];
}
_mapParameterName2FactMetaData.clear();
_parameterMetaDataLoaded = false;
}
/// Override from FactLoad which connects the meta data to the fact /// Override from FactLoad which connects the meta data to the fact
void APMParameterLoader::_addMetaDataToFact(Fact* fact) void APMParameterMetaData::addMetaDataToFact(Fact* fact)
{ {
// FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data // FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data
// Use generic meta data FactMetaData* metaData = new FactMetaData(fact->type(), fact);
ParameterLoader::_addMetaDataToFact(fact); fact->setMetaData(metaData);
} }
...@@ -21,15 +21,14 @@ ...@@ -21,15 +21,14 @@
======================================================================*/ ======================================================================*/
#ifndef APMParameterLoader_H #ifndef APMParameterMetaData_H
#define APMParameterLoader_H #define APMParameterMetaData_H
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
#include <QXmlStreamReader> #include <QXmlStreamReader>
#include <QLoggingCategory> #include <QLoggingCategory>
#include "ParameterLoader.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "Vehicle.h" #include "Vehicle.h"
...@@ -37,24 +36,24 @@ ...@@ -37,24 +36,24 @@
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(APMParameterLoaderLog) Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog)
/// Collection of Parameter Facts for PX4 AutoPilot /// Collection of Parameter Facts for PX4 AutoPilot
class APMParameterLoader : public ParameterLoader class APMParameterMetaData : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); APMParameterMetaData(QObject* parent = NULL);
/// Override from ParameterLoader /// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
static void loadParameterFactMetaData(void);
static void clearStaticData(void);
// Overrides from ParameterLoader
static void addMetaDataToFact(Fact* fact);
private: private:
enum { enum {
XmlStateNone, XmlStateNone,
...@@ -65,10 +64,8 @@ private: ...@@ -65,10 +64,8 @@ private:
XmlStateDone XmlStateDone
}; };
// Overrides from ParameterLoader
virtual void _addMetaDataToFact(Fact* fact);
// Class methods static void _loadParameterFactMetaData(void);
static 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 static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
......
...@@ -105,8 +105,11 @@ public: ...@@ -105,8 +105,11 @@ public:
/// 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) = 0;
/// Returns the ParameterLoader /// Returns the parameter that is used to identify the default component
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) = 0; virtual QString getDefaultComponentIdParam(void) const = 0;
/// Adds the parameter meta data to the Fact
virtual void addMetaDataToFact(Fact* fact) = 0;
protected: protected:
FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { } FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { }
......
...@@ -33,7 +33,6 @@ IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) ...@@ -33,7 +33,6 @@ IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin)
GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent) : FirmwarePlugin(parent)
, _parameterLoader(NULL)
{ {
} }
...@@ -121,16 +120,9 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -121,16 +120,9 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
return false; return false;
} }
ParameterLoader* GenericFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact)
{ {
if (!_parameterLoader) { // Add default meta data
_parameterLoader = new GenericParameterLoader(autopilotPlugin, vehicle, this); FactMetaData* metaData = new FactMetaData(fact->type(), fact);
Q_CHECK_PTR(_parameterLoader); fact->setMetaData(metaData);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &GenericParameterLoader::parameterListProgress, autopilotPlugin, &GenericAutoPilotPlugin::parameterListProgress);
}
return _parameterLoader;
} }
...@@ -28,7 +28,6 @@ ...@@ -28,7 +28,6 @@
#define GenericFirmwarePlugin_H #define GenericFirmwarePlugin_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "GenericParameterLoader.h"
class GenericFirmwarePlugin : public FirmwarePlugin class GenericFirmwarePlugin : public FirmwarePlugin
{ {
...@@ -48,13 +47,12 @@ public: ...@@ -48,13 +47,12 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle); virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
private: private:
/// All access to singleton is through AutoPilotPluginManager::instance /// All access to singleton is through AutoPilotPluginManager::instance
GenericFirmwarePlugin(QObject* parent = NULL); GenericFirmwarePlugin(QObject* parent = NULL);
GenericParameterLoader* _parameterLoader;
}; };
#endif #endif
/*=====================================================================
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/>.
======================================================================*/
#include "GenericParameterLoader.h"
GenericParameterLoader::GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) :
ParameterLoader(autopilot, vehicle, parent)
{
Q_ASSERT(vehicle);
}
/// Override from ParameterLoader which connects the meta data to the fact
void GenericParameterLoader::_addMetaDataToFact(Fact* fact)
{
// Use generic meta data
ParameterLoader::_addMetaDataToFact(fact);
}
/*=====================================================================
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/>.
======================================================================*/
#ifndef GenericParameterLoader_H
#define GenericParameterLoader_H
#include "ParameterLoader.h"
#include "FactSystem.h"
#include "AutoPilotPlugin.h"
#include "Vehicle.h"
class GenericParameterLoader : public ParameterLoader
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
private:
// Overrides from ParameterLoader
virtual void _addMetaDataToFact(Fact* fact);
};
#endif
...@@ -90,7 +90,6 @@ static const struct Modes2Name rgModes2Name[] = { ...@@ -90,7 +90,6 @@ static const struct Modes2Name rgModes2Name[] = {
PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent)
: FirmwarePlugin(parent) : FirmwarePlugin(parent)
, _parameterLoader(NULL)
{ {
} }
...@@ -212,18 +211,7 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -212,18 +211,7 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return false; return false;
} }
ParameterLoader* PX4FirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact)
{ {
if (!_parameterLoader) { _parameterMetaData.addMetaDataToFact(fact);
_parameterLoader = new PX4ParameterLoader(autopilotPlugin, vehicle, this);
Q_CHECK_PTR(_parameterLoader);
// FIXME: Why do I need SIGNAL/SLOT to make this work
connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, &PX4ParameterLoader::parameterListProgress, autopilotPlugin, &PX4AutoPilotPlugin::parameterListProgress);
_parameterLoader->loadParameterFactMetaData();
}
return _parameterLoader;
} }
...@@ -28,7 +28,7 @@ ...@@ -28,7 +28,7 @@
#define PX4FirmwarePlugin_H #define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "PX4ParameterLoader.h" #include "PX4ParameterMetaData.h"
class PX4FirmwarePlugin : public FirmwarePlugin class PX4FirmwarePlugin : public FirmwarePlugin
{ {
...@@ -48,13 +48,14 @@ public: ...@@ -48,13 +48,14 @@ public:
virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle); virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
private: private:
/// All access to singleton is through AutoPilotPluginManager::instance /// All access to singleton is through AutoPilotPluginManager::instance
PX4FirmwarePlugin(QObject* parent = NULL); PX4FirmwarePlugin(QObject* parent = NULL);
PX4ParameterLoader* _parameterLoader; PX4ParameterMetaData _parameterMetaData;
}; };
#endif #endif
...@@ -21,15 +21,14 @@ ...@@ -21,15 +21,14 @@
======================================================================*/ ======================================================================*/
#ifndef PX4PARAMETERLOADER_H #ifndef PX4ParameterMetaData_H
#define PX4PARAMETERLOADER_H #define PX4ParameterMetaData_H
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
#include <QXmlStreamReader> #include <QXmlStreamReader>
#include <QLoggingCategory> #include <QLoggingCategory>
#include "ParameterLoader.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "Vehicle.h" #include "Vehicle.h"
...@@ -37,24 +36,19 @@ ...@@ -37,24 +36,19 @@
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(PX4ParameterLoaderLog) Q_DECLARE_LOGGING_CATEGORY(PX4ParameterMetaDataLog)
/// Collection of Parameter Facts for PX4 AutoPilot /// Collection of Parameter Facts for PX4 AutoPilot
class PX4ParameterLoader : public ParameterLoader class PX4ParameterMetaData : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
/// @param uas Uas which this set of facts is associated with PX4ParameterMetaData(QObject* parent = NULL);
PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL);
void addMetaDataToFact(Fact* fact);
/// Override from ParameterLoader
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
static void loadParameterFactMetaData(void);
static void clearStaticData(void);
private: private:
enum { enum {
XmlStateNone, XmlStateNone,
...@@ -63,16 +57,13 @@ private: ...@@ -63,16 +57,13 @@ private:
XmlStateFoundGroup, XmlStateFoundGroup,
XmlStateFoundParameter, XmlStateFoundParameter,
XmlStateDone XmlStateDone
}; };
// Overrides from ParameterLoader
virtual void _addMetaDataToFact(Fact* fact);
// Class methods static void _loadParameterFactMetaData(void);
static 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 static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded
static QMap<QString, FactMetaData*> _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData static QMap<QString, FactMetaData*> _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
}; };
#endif #endif
\ No newline at end of file
...@@ -32,6 +32,7 @@ ...@@ -32,6 +32,7 @@
#include "JoystickManager.h" #include "JoystickManager.h"
#include "MissionManager.h" #include "MissionManager.h"
#include "CoordinateVector.h" #include "CoordinateVector.h"
#include "ParameterLoader.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
...@@ -89,6 +90,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, ...@@ -89,6 +90,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
, _updateCount(0) , _updateCount(0)
, _missionManager(NULL) , _missionManager(NULL)
, _missionManagerInitialRequestComplete(false) , _missionManagerInitialRequestComplete(false)
, _parameterLoader(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -154,9 +156,13 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, ...@@ -154,9 +156,13 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType,
_loadSettings(); _loadSettings();
_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 */);
connect(_parameterLoader, SIGNAL(parametersReady(bool)), _autopilotPlugin, SLOT(_parametersReadyPreChecks(bool)));
connect(_parameterLoader, SIGNAL(parameterListProgress(float)), _autopilotPlugin, SLOT(parameterListProgress(float)));
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
_sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay); _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
...@@ -1148,3 +1154,8 @@ void Vehicle::_communicationInactivityTimedOut(void) ...@@ -1148,3 +1154,8 @@ void Vehicle::_communicationInactivityTimedOut(void)
linkMgr->disconnectLink(_links[i].data()); linkMgr->disconnectLink(_links[i].data());
} }
} }
ParameterLoader* Vehicle::getParameterLoader(void)
{
return _parameterLoader;
}
...@@ -42,6 +42,7 @@ class UASInterface; ...@@ -42,6 +42,7 @@ class UASInterface;
class FirmwarePlugin; class FirmwarePlugin;
class AutoPilotPlugin; class AutoPilotPlugin;
class MissionManager; class MissionManager;
class ParameterLoader;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog) Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
...@@ -248,6 +249,8 @@ public: ...@@ -248,6 +249,8 @@ public:
double waypointDistance () { return _waypointDistance; } double waypointDistance () { return _waypointDistance; }
uint16_t currentWaypoint () { return _currentWaypoint; } uint16_t currentWaypoint () { return _currentWaypoint; }
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; }
ParameterLoader* getParameterLoader(void);
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
...@@ -411,6 +414,8 @@ private: ...@@ -411,6 +414,8 @@ private:
MissionManager* _missionManager; MissionManager* _missionManager;
bool _missionManagerInitialRequestComplete; bool _missionManagerInitialRequestComplete;
ParameterLoader* _parameterLoader;
bool _armed; ///< true: vehicle is armed bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT uint8_t _base_mode; ///< base_mode from HEARTBEAT
......
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