Commit d9d73080 authored by Don Gagne's avatar Don Gagne

ParameterLoader -> ParameterManager

parent 4b4ece63
...@@ -580,6 +580,7 @@ HEADERS += \ ...@@ -580,6 +580,7 @@ HEADERS += \
src/FactSystem/FactSystemTestBase.h \ src/FactSystem/FactSystemTestBase.h \
src/FactSystem/FactSystemTestGeneric.h \ src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \ src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/ComplexMissionItemTest.h \ src/MissionManager/ComplexMissionItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \ src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerTest.h \ src/MissionManager/MissionControllerTest.h \
...@@ -596,7 +597,6 @@ HEADERS += \ ...@@ -596,7 +597,6 @@ HEADERS += \
src/qgcunittest/MavlinkLogTest.h \ src/qgcunittest/MavlinkLogTest.h \
src/qgcunittest/MessageBoxTest.h \ src/qgcunittest/MessageBoxTest.h \
src/qgcunittest/MultiSignalSpy.h \ src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/ParameterLoaderTest.h \
src/qgcunittest/RadioConfigTest.h \ src/qgcunittest/RadioConfigTest.h \
src/qgcunittest/TCPLinkTest.h \ src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h \ src/qgcunittest/TCPLoopBackServer.h \
...@@ -608,6 +608,7 @@ SOURCES += \ ...@@ -608,6 +608,7 @@ SOURCES += \
src/FactSystem/FactSystemTestBase.cc \ src/FactSystem/FactSystemTestBase.cc \
src/FactSystem/FactSystemTestGeneric.cc \ src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \ src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/ComplexMissionItemTest.cc \ src/MissionManager/ComplexMissionItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \ src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerTest.cc \ src/MissionManager/MissionControllerTest.cc \
...@@ -624,7 +625,6 @@ SOURCES += \ ...@@ -624,7 +625,6 @@ SOURCES += \
src/qgcunittest/MavlinkLogTest.cc \ src/qgcunittest/MavlinkLogTest.cc \
src/qgcunittest/MessageBoxTest.cc \ src/qgcunittest/MessageBoxTest.cc \
src/qgcunittest/MultiSignalSpy.cc \ src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/ParameterLoaderTest.cc \
src/qgcunittest/RadioConfigTest.cc \ src/qgcunittest/RadioConfigTest.cc \
src/qgcunittest/TCPLinkTest.cc \ src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc \ src/qgcunittest/TCPLoopBackServer.cc \
...@@ -787,7 +787,7 @@ HEADERS += \ ...@@ -787,7 +787,7 @@ HEADERS += \
src/FactSystem/FactMetaData.h \ src/FactSystem/FactMetaData.h \
src/FactSystem/FactSystem.h \ src/FactSystem/FactSystem.h \
src/FactSystem/FactValidator.h \ src/FactSystem/FactValidator.h \
src/FactSystem/ParameterLoader.h \ src/FactSystem/ParameterManager.h \
src/FactSystem/SettingsFact.h \ src/FactSystem/SettingsFact.h \
SOURCES += \ SOURCES += \
...@@ -797,7 +797,7 @@ SOURCES += \ ...@@ -797,7 +797,7 @@ SOURCES += \
src/FactSystem/FactMetaData.cc \ src/FactSystem/FactMetaData.cc \
src/FactSystem/FactSystem.cc \ src/FactSystem/FactSystem.cc \
src/FactSystem/FactValidator.cc \ src/FactSystem/FactValidator.cc \
src/FactSystem/ParameterLoader.cc \ src/FactSystem/ParameterManager.cc \
src/FactSystem/SettingsFact.cc \ src/FactSystem/SettingsFact.cc \
#------------------------------------------------------------------------------------- #-------------------------------------------------------------------------------------
......
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
#include <QXmlStreamReader> #include <QXmlStreamReader>
#include <QLoggingCategory> #include <QLoggingCategory>
#include "ParameterLoader.h" #include "ParameterManager.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
......
...@@ -13,7 +13,7 @@ ...@@ -13,7 +13,7 @@
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
#include "UAS.h" #include "UAS.h"
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
...@@ -104,24 +104,24 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void) ...@@ -104,24 +104,24 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
void AutoPilotPlugin::refreshAllParameters(unsigned char componentID) void AutoPilotPlugin::refreshAllParameters(unsigned char componentID)
{ {
_vehicle->getParameterLoader()->refreshAllParameters((uint8_t)componentID); _vehicle->getParameterManager()->refreshAllParameters((uint8_t)componentID);
} }
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name) void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{ {
_vehicle->getParameterLoader()->refreshParameter(componentId, name); _vehicle->getParameterManager()->refreshParameter(componentId, name);
} }
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix) void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
{ {
_vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); _vehicle->getParameterManager()->refreshParametersPrefix(componentId, namePrefix);
} }
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 _vehicle->getParameterLoader()->parameterExists(componentId, name); return _vehicle->getParameterManager()->parameterExists(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -134,7 +134,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -134,7 +134,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
{ {
switch (provider) { switch (provider) {
case FactSystem::ParameterProvider: case FactSystem::ParameterProvider:
return _vehicle->getParameterLoader()->getFact(componentId, name); return _vehicle->getParameterManager()->getFact(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -145,20 +145,15 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -145,20 +145,15 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
QStringList AutoPilotPlugin::parameterNames(int componentId) QStringList AutoPilotPlugin::parameterNames(int componentId)
{ {
return _vehicle->getParameterLoader()->parameterNames(componentId); return _vehicle->getParameterManager()->parameterNames(componentId);
}
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{
return _vehicle->getParameterLoader()->getGroupMap();
} }
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{ {
_vehicle->getParameterLoader()->writeParametersToStream(stream); _vehicle->getParameterManager()->writeParametersToStream(stream);
} }
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{ {
return _vehicle->getParameterLoader()->readParametersFromStream(stream); return _vehicle->getParameterManager()->readParametersFromStream(stream);
} }
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
#include "FactSystem.h" #include "FactSystem.h"
#include "Vehicle.h" #include "Vehicle.h"
class ParameterLoader; class ParameterManager;
class Vehicle; class Vehicle;
class FirmwarePlugin; class FirmwarePlugin;
...@@ -84,8 +84,6 @@ public: ...@@ -84,8 +84,6 @@ public:
int componentId, ///< fact component, -1=default component int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name const QString& name); ///< fact name
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
// Must be implemented by derived class // Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0; virtual const QVariantList& vehicleComponents(void) = 0;
......
...@@ -16,7 +16,7 @@ ...@@ -16,7 +16,7 @@
#include <QXmlStreamReader> #include <QXmlStreamReader>
#include <QLoggingCategory> #include <QLoggingCategory>
#include "ParameterLoader.h" #include "ParameterManager.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
......
...@@ -8,8 +8,8 @@ ...@@ -8,8 +8,8 @@
****************************************************************************/ ****************************************************************************/
#ifndef PARAMETERLOADER_H #ifndef ParameterManager_H
#define PARAMETERLOADER_H #define ParameterManager_H
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#include <QLoggingCategory> #include <QLoggingCategory>
#include <QMutex> #include <QMutex>
#include <QDir> #include <QDir>
#include <QJsonObject>
#include "FactSystem.h" #include "FactSystem.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
...@@ -27,18 +28,18 @@ ...@@ -27,18 +28,18 @@
/// @file /// @file
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerboseLog)
/// Connects to Parameter Manager to load/update Facts /// Connects to Parameter Manager to load/update Facts
class ParameterLoader : public QObject class ParameterManager : 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
ParameterLoader(Vehicle* vehicle); ParameterManager(Vehicle* vehicle);
~ParameterLoader(); ~ParameterManager();
/// @return Directory of parameter caches /// @return Directory of parameter caches
static QDir parameterCacheDir(); static QDir parameterCacheDir();
...@@ -91,8 +92,21 @@ public: ...@@ -91,8 +92,21 @@ public:
/// If this file is newer than anything in the cache, cache it as the latest version /// 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); static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType);
int defaultComponenentId(void) { return _defaultComponentId; } int defaultComponentId(void) { return _defaultComponentId; }
/// Saves the specified param set to the json object.
/// @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components
/// @param paramsToSave List of params names to save, empty to save all for component
/// @param saveObject Json object to save to
void saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject);
/// Load a parameter set from json
/// @param json Json object to load from
/// @param required true: no parameters in object will generate error
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
signals: signals:
/// Signalled when the full set of facts are ready /// Signalled when the full set of facts are ready
void parametersReady(bool missingParameters); void parametersReady(bool missingParameters);
...@@ -179,6 +193,10 @@ private: ...@@ -179,6 +193,10 @@ private:
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; static const char* _cachedMetaDataFilePrefix;
static const char* _jsonParametersKey;
static const char* _jsonCompIdKey;
static const char* _jsonParamNameKey;
static const char* _jsonParamValueKey;
}; };
#endif #endif
...@@ -8,13 +8,13 @@ ...@@ -8,13 +8,13 @@
****************************************************************************/ ****************************************************************************/
#include "ParameterLoaderTest.h" #include "ParameterManagerTest.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
/// Test failure modes which should still lead to param load success /// Test failure modes which should still lead to param load success
void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t failureMode) void ParameterManagerTest::_noFailureWorker(MockConfiguration::FailureMode_t failureMode)
{ {
Q_ASSERT(!_mockLink); Q_ASSERT(!_mockLink);
_mockLink = MockLink::startPX4MockLink(false, failureMode); _mockLink = MockLink::startPX4MockLink(false, failureMode);
...@@ -34,7 +34,7 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail ...@@ -34,7 +34,7 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail
QVERIFY(vehicle); QVERIFY(vehicle);
// We should get progress bar updates during load // We should get progress bar updates during load
QSignalSpy spyProgress(vehicle->getParameterLoader(), SIGNAL(parameterListProgress(float))); QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float)));
QCOMPARE(spyProgress.wait(2000), true); QCOMPARE(spyProgress.wait(2000), true);
arguments = spyProgress.takeFirst(); arguments = spyProgress.takeFirst();
QCOMPARE(arguments.count(), 1); QCOMPARE(arguments.count(), 1);
...@@ -54,18 +54,18 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail ...@@ -54,18 +54,18 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail
} }
void ParameterLoaderTest::_noFailure(void) void ParameterManagerTest::_noFailure(void)
{ {
_noFailureWorker(MockConfiguration::FailNone); _noFailureWorker(MockConfiguration::FailNone);
} }
void ParameterLoaderTest::_requestListMissingParamSuccess(void) void ParameterManagerTest::_requestListMissingParamSuccess(void)
{ {
_noFailureWorker(MockConfiguration::FailMissingParamOnInitialReqest); _noFailureWorker(MockConfiguration::FailMissingParamOnInitialReqest);
} }
// Test no response to param_request_list // Test no response to param_request_list
void ParameterLoaderTest::_requestListNoResponse(void) void ParameterManagerTest::_requestListNoResponse(void)
{ {
Q_ASSERT(!_mockLink); Q_ASSERT(!_mockLink);
_mockLink = MockLink::startPX4MockLink(false, MockConfiguration::FailParamNoReponseToRequestList); _mockLink = MockLink::startPX4MockLink(false, MockConfiguration::FailParamNoReponseToRequestList);
...@@ -85,7 +85,7 @@ void ParameterLoaderTest::_requestListNoResponse(void) ...@@ -85,7 +85,7 @@ void ParameterLoaderTest::_requestListNoResponse(void)
QVERIFY(vehicle); QVERIFY(vehicle);
QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QSignalSpy spyProgress(vehicle->getParameterLoader(), SIGNAL(parameterListProgress(float))); QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float)));
// We should not get any progress bar updates, nor a parameter ready signal // We should not get any progress bar updates, nor a parameter ready signal
QCOMPARE(spyProgress.wait(500), false); QCOMPARE(spyProgress.wait(500), false);
...@@ -97,7 +97,7 @@ void ParameterLoaderTest::_requestListNoResponse(void) ...@@ -97,7 +97,7 @@ void ParameterLoaderTest::_requestListNoResponse(void)
// MockLink will fail to send a param on initial request, it will also fail to send it on subsequent // MockLink will fail to send a param on initial request, it will also fail to send it on subsequent
// param_read requests. // param_read requests.
void ParameterLoaderTest::_requestListMissingParamFail(void) void ParameterManagerTest::_requestListMissingParamFail(void)
{ {
// Will pop error about missing params // Will pop error about missing params
setExpectedMessageBox(QMessageBox::Ok); setExpectedMessageBox(QMessageBox::Ok);
...@@ -120,7 +120,7 @@ void ParameterLoaderTest::_requestListMissingParamFail(void) ...@@ -120,7 +120,7 @@ void ParameterLoaderTest::_requestListMissingParamFail(void)
QVERIFY(vehicle); QVERIFY(vehicle);
QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool)));
QSignalSpy spyProgress(vehicle->getParameterLoader(), SIGNAL(parameterListProgress(float))); QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float)));
// We will get progress bar updates, since it will fail after getting partially through the request // We will get progress bar updates, since it will fail after getting partially through the request
QCOMPARE(spyProgress.wait(2000), true); QCOMPARE(spyProgress.wait(2000), true);
......
...@@ -8,15 +8,15 @@ ...@@ -8,15 +8,15 @@
****************************************************************************/ ****************************************************************************/
#ifndef ParameterLoaderTest_H #ifndef ParameterManagerTest_H
#define ParameterLoaderTest_H #define ParameterManagerTest_H
#include "UnitTest.h" #include "UnitTest.h"
#include "MockLink.h" #include "MockLink.h"
#include "MultiSignalSpy.h" #include "MultiSignalSpy.h"
#include "MockLink.h" #include "MockLink.h"
class ParameterLoaderTest : public UnitTest class ParameterManagerTest : public UnitTest
{ {
Q_OBJECT Q_OBJECT
......
...@@ -12,7 +12,7 @@ ...@@ -12,7 +12,7 @@
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
const char* APMGeoFenceManager::_fenceTotalParam = "FENCE_TOTAL"; const char* APMGeoFenceManager::_fenceTotalParam = "FENCE_TOTAL";
const char* APMGeoFenceManager::_fenceActionParam = "FENCE_ACTION"; const char* APMGeoFenceManager::_fenceActionParam = "FENCE_ACTION";
...@@ -30,9 +30,9 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) ...@@ -30,9 +30,9 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
, _fenceTypeFact(NULL) , _fenceTypeFact(NULL)
{ {
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived);
connect(_vehicle->getParameterLoader(), &ParameterLoader::parametersReady, this, &APMGeoFenceManager::_parametersReady); connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &APMGeoFenceManager::_parametersReady);
if (_vehicle->getParameterLoader()->parametersAreReady()) { if (_vehicle->getParameterManager()->parametersAreReady()) {
_parametersReady(); _parametersReady();
} }
} }
......
...@@ -15,7 +15,7 @@ ...@@ -15,7 +15,7 @@
#define PX4FirmwarePlugin_H #define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
#include "PX4ParameterMetaData.h" #include "PX4ParameterMetaData.h"
#include "PX4GeoFenceManager.h" #include "PX4GeoFenceManager.h"
...@@ -57,6 +57,7 @@ public: ...@@ -57,6 +57,7 @@ public:
QObject* loadParameterMetaData (const QString& metaDataFile); QObject* loadParameterMetaData (const QString& metaDataFile);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message); bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message);
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new PX4GeoFenceManager(vehicle); } GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new PX4GeoFenceManager(vehicle); }
QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
// Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the // Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the
// names may change. // names may change.
......
...@@ -10,14 +10,14 @@ ...@@ -10,14 +10,14 @@
#include "PX4GeoFenceManager.h" #include "PX4GeoFenceManager.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle) : GeoFenceManager(vehicle)
, _firstParamLoadComplete(false) , _firstParamLoadComplete(false)
, _circleRadiusFact(NULL) , _circleRadiusFact(NULL)
{ {
connect(_vehicle->getParameterLoader(), &ParameterLoader::parametersReady, this, &PX4GeoFenceManager::_parametersReady); connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &PX4GeoFenceManager::_parametersReady);
} }
PX4GeoFenceManager::~PX4GeoFenceManager() PX4GeoFenceManager::~PX4GeoFenceManager()
......
...@@ -64,7 +64,7 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact ...@@ -64,7 +64,7 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile) void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
{ {
qCDebug(ParameterLoaderLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile; qCDebug(ParameterManagerLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile;
if (_parameterMetaDataLoaded) { if (_parameterMetaDataLoaded) {
qWarning() << "Internal error: parameter meta data loaded more than once"; qWarning() << "Internal error: parameter meta data loaded more than once";
......
...@@ -20,7 +20,7 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog") ...@@ -20,7 +20,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") QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGCLoggingCategoryRegister* _instance = NULL; QGCLoggingCategoryRegister* _instance = NULL;
const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters"; const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters";
......
...@@ -22,7 +22,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog) ...@@ -22,7 +22,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) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
/// @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
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include "ParameterEditorController.h" #include "ParameterEditorController.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterManager.h"
#ifndef __mobile__ #ifndef __mobile__
#include "QGCFileDialog.h" #include "QGCFileDialog.h"
...@@ -28,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void) ...@@ -28,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void)
: _currentComponentId(_vehicle->defaultComponentId()) : _currentComponentId(_vehicle->defaultComponentId())
, _parameters(new QmlObjectListModel(this)) , _parameters(new QmlObjectListModel(this))
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap();
foreach (int componentId, groupMap.keys()) { foreach (int componentId, groupMap.keys()) {
_componentIds += QString("%1").arg(componentId); _componentIds += QString("%1").arg(componentId);
} }
...@@ -48,14 +49,14 @@ ParameterEditorController::~ParameterEditorController() ...@@ -48,14 +49,14 @@ ParameterEditorController::~ParameterEditorController()
QStringList ParameterEditorController::getGroupsForComponent(int componentId) QStringList ParameterEditorController::getGroupsForComponent(int componentId)
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap();
return groupMap[componentId].keys(); return groupMap[componentId].keys();
} }
QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group) QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group)
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap();
return groupMap[componentId][group]; return groupMap[componentId][group];
} }
...@@ -187,7 +188,7 @@ void ParameterEditorController::_updateParameters(void) ...@@ -187,7 +188,7 @@ void ParameterEditorController::_updateParameters(void)
QObjectList newParameterList; QObjectList newParameterList;
if (_searchText.isEmpty()) { if (_searchText.isEmpty()) {
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap();
foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) {
newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter)); newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter));
} }
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
#include "JoystickManager.h" #include "JoystickManager.h"
#include "MissionManager.h" #include "MissionManager.h"
#include "CoordinateVector.h" #include "CoordinateVector.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCImageProvider.h" #include "QGCImageProvider.h"
#include "GAudioOutput.h" #include "GAudioOutput.h"
...@@ -199,11 +199,11 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -199,11 +199,11 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable);
_parameterLoader = new ParameterLoader(this); _parameterLoader = new ParameterManager(this);
connect(_parameterLoader, &ParameterLoader::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks); connect(_parameterLoader, &ParameterManager::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); connect(_parameterLoader, &ParameterManager::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
// GeoFenceManager needs to access ParameterLoader so make sure to create after // GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError); connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
...@@ -332,9 +332,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -332,9 +332,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_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(this); _parameterLoader = new ParameterManager(this);
// GeoFenceManager needs to access ParameterLoader so make sure to create after // GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError); connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
...@@ -1813,7 +1813,7 @@ void Vehicle::rebootVehicle() ...@@ -1813,7 +1813,7 @@ void Vehicle::rebootVehicle()
int Vehicle::defaultComponentId(void) int Vehicle::defaultComponentId(void)
{ {
return _parameterLoader->defaultComponenentId(); return _parameterLoader->defaultComponentId();
} }
void Vehicle::setSoloFirmware(bool soloFirmware) void Vehicle::setSoloFirmware(bool soloFirmware)
...@@ -1835,7 +1835,7 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs) ...@@ -1835,7 +1835,7 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
/// Returns true if the specifed parameter exists from the default component /// Returns true if the specifed parameter exists from the default component
bool Vehicle::parameterExists(int componentId, const QString& name) const bool Vehicle::parameterExists(int componentId, const QString& name) const
{ {
return getParameterLoader()->parameterExists(componentId, name); return getParameterManager()->parameterExists(componentId, name);
} }
/// Returns the specified parameter Fact from the default component /// Returns the specified parameter Fact from the default component
...@@ -1843,7 +1843,7 @@ bool Vehicle::parameterExists(int componentId, const QString& name) const ...@@ -1843,7 +1843,7 @@ bool Vehicle::parameterExists(int componentId, const QString& name) const
/// parameterExists. /// parameterExists.
Fact* Vehicle::getParameterFact(int componentId, const QString& name) Fact* Vehicle::getParameterFact(int componentId, const QString& name)
{ {
return getParameterLoader()->getFact(componentId, name); return getParameterManager()->getFact(componentId, name);
} }
void Vehicle::_newMissionItemsAvailable(void) void Vehicle::_newMissionItemsAvailable(void)
......
...@@ -34,7 +34,7 @@ class AutoPilotPlugin; ...@@ -34,7 +34,7 @@ class AutoPilotPlugin;
class AutoPilotPluginManager; class AutoPilotPluginManager;
class MissionManager; class MissionManager;
class GeoFenceManager; class GeoFenceManager;
class ParameterLoader; class ParameterManager;
class JoystickManager; class JoystickManager;
class UASMessage; class UASMessage;
...@@ -544,8 +544,8 @@ public: ...@@ -544,8 +544,8 @@ public:
void setConnectionLostEnabled(bool connectionLostEnabled); void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterLoader* getParameterLoader(void) { return _parameterLoader; } ParameterManager* getParameterManager(void) { return _parameterLoader; }
ParameterLoader* getParameterLoader(void) const { return _parameterLoader; } ParameterManager* getParameterManager(void) const { return _parameterLoader; }
static const int cMaxRcChannels = 18; static const int cMaxRcChannels = 18;
...@@ -763,7 +763,7 @@ private: ...@@ -763,7 +763,7 @@ private:
GeoFenceManager* _geoFenceManager; GeoFenceManager* _geoFenceManager;
bool _geoFenceManagerInitialRequestComplete; bool _geoFenceManagerInitialRequestComplete;
ParameterLoader* _parameterLoader; ParameterManager* _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
......
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "FirmwarePlugin.h" #include "FirmwarePlugin.h"
#include "ParameterLoader.h" #include "ParameterManager.h"
#include <QDebug> #include <QDebug>
#include <QFile> #include <QFile>
...@@ -275,7 +275,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) ...@@ -275,7 +275,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
} }
// Cache this file with the system // Cache this file with the system
ParameterLoader::cacheMetaDataFile(parameterFilename, firmwareType); ParameterManager::cacheMetaDataFile(parameterFilename, firmwareType);
} }
// Decompress the airframe xml and save to file // Decompress the airframe xml and save to file
......
...@@ -29,7 +29,7 @@ ...@@ -29,7 +29,7 @@
#include "MainWindowTest.h" #include "MainWindowTest.h"
#include "FileManagerTest.h" #include "FileManagerTest.h"
#include "TCPLinkTest.h" #include "TCPLinkTest.h"
#include "ParameterLoaderTest.h" #include "ParameterManagerTest.h"
#include "MissionCommandTreeTest.h" #include "MissionCommandTreeTest.h"
#include "LogDownloadTest.h" #include "LogDownloadTest.h"
...@@ -49,7 +49,7 @@ UT_REGISTER_TEST(MissionManagerTest) ...@@ -49,7 +49,7 @@ UT_REGISTER_TEST(MissionManagerTest)
UT_REGISTER_TEST(RadioConfigTest) UT_REGISTER_TEST(RadioConfigTest)
UT_REGISTER_TEST(TCPLinkTest) UT_REGISTER_TEST(TCPLinkTest)
UT_REGISTER_TEST(FileManagerTest) UT_REGISTER_TEST(FileManagerTest)
UT_REGISTER_TEST(ParameterLoaderTest) UT_REGISTER_TEST(ParameterManagerTest)
UT_REGISTER_TEST(MissionCommandTreeTest) UT_REGISTER_TEST(MissionCommandTreeTest)
UT_REGISTER_TEST(LogDownloadTest) UT_REGISTER_TEST(LogDownloadTest)
......
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