Commit d9d73080 authored by Don Gagne's avatar Don Gagne

ParameterLoader -> ParameterManager

parent 4b4ece63
......@@ -580,6 +580,7 @@ HEADERS += \
src/FactSystem/FactSystemTestBase.h \
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/ComplexMissionItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerTest.h \
......@@ -596,7 +597,6 @@ HEADERS += \
src/qgcunittest/MavlinkLogTest.h \
src/qgcunittest/MessageBoxTest.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/ParameterLoaderTest.h \
src/qgcunittest/RadioConfigTest.h \
src/qgcunittest/TCPLinkTest.h \
src/qgcunittest/TCPLoopBackServer.h \
......@@ -608,6 +608,7 @@ SOURCES += \
src/FactSystem/FactSystemTestBase.cc \
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/ComplexMissionItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerTest.cc \
......@@ -624,7 +625,6 @@ SOURCES += \
src/qgcunittest/MavlinkLogTest.cc \
src/qgcunittest/MessageBoxTest.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/ParameterLoaderTest.cc \
src/qgcunittest/RadioConfigTest.cc \
src/qgcunittest/TCPLinkTest.cc \
src/qgcunittest/TCPLoopBackServer.cc \
......@@ -787,7 +787,7 @@ HEADERS += \
src/FactSystem/FactMetaData.h \
src/FactSystem/FactSystem.h \
src/FactSystem/FactValidator.h \
src/FactSystem/ParameterLoader.h \
src/FactSystem/ParameterManager.h \
src/FactSystem/SettingsFact.h \
SOURCES += \
......@@ -797,7 +797,7 @@ SOURCES += \
src/FactSystem/FactMetaData.cc \
src/FactSystem/FactSystem.cc \
src/FactSystem/FactValidator.cc \
src/FactSystem/ParameterLoader.cc \
src/FactSystem/ParameterManager.cc \
src/FactSystem/SettingsFact.cc \
#-------------------------------------------------------------------------------------
......
......@@ -16,7 +16,7 @@
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "FactSystem.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
......
......@@ -13,7 +13,7 @@
#include "AutoPilotPlugin.h"
#include "QGCApplication.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "UAS.h"
#include "FirmwarePlugin.h"
......@@ -104,24 +104,24 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void)
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)
{
_vehicle->getParameterLoader()->refreshParameter(componentId, name);
_vehicle->getParameterManager()->refreshParameter(componentId, name);
}
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)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterLoader()->parameterExists(componentId, name);
return _vehicle->getParameterManager()->parameterExists(componentId, name);
// Other providers will go here once they come online
}
......@@ -134,7 +134,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterLoader()->getFact(componentId, name);
return _vehicle->getParameterManager()->getFact(componentId, name);
// Other providers will go here once they come online
}
......@@ -145,20 +145,15 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
QStringList AutoPilotPlugin::parameterNames(int componentId)
{
return _vehicle->getParameterLoader()->parameterNames(componentId);
}
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{
return _vehicle->getParameterLoader()->getGroupMap();
return _vehicle->getParameterManager()->parameterNames(componentId);
}
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_vehicle->getParameterLoader()->writeParametersToStream(stream);
_vehicle->getParameterManager()->writeParametersToStream(stream);
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
return _vehicle->getParameterLoader()->readParametersFromStream(stream);
return _vehicle->getParameterManager()->readParametersFromStream(stream);
}
......@@ -19,7 +19,7 @@
#include "FactSystem.h"
#include "Vehicle.h"
class ParameterLoader;
class ParameterManager;
class Vehicle;
class FirmwarePlugin;
......@@ -84,8 +84,6 @@ public:
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
// Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0;
......
......@@ -16,7 +16,7 @@
#include <QXmlStreamReader>
#include <QLoggingCategory>
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "FactSystem.h"
#include "UASInterface.h"
#include "AutoPilotPlugin.h"
......
......@@ -11,7 +11,7 @@
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
......@@ -19,24 +19,30 @@
#include "FirmwarePlugin.h"
#include "APMFirmwarePlugin.h"
#include "UAS.h"
#include "JsonHelper.h"
#include <QEasingCurve>
#include <QFile>
#include <QDebug>
#include <QVariantAnimation>
#include <QJsonArray>
/* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam;
typedef QMap<int, NamedParam> MapID2NamedParam;
QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
QGC_LOGGING_CATEGORY(ParameterManagerVerboseLog, "ParameterManagerVerboseLog")
Fact ParameterLoader::_defaultFact;
Fact ParameterManager::_defaultFact;
const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
const char* ParameterManager::_cachedMetaDataFilePrefix = "ParameterFactMetaData";
const char* ParameterManager::_jsonParametersKey = "parameters";
const char* ParameterManager::_jsonCompIdKey = "compId";
const char* ParameterManager::_jsonParamNameKey = "name";
const char* ParameterManager::_jsonParamValueKey = "value";
ParameterLoader::ParameterLoader(Vehicle* vehicle)
ParameterManager::ParameterManager(Vehicle* vehicle)
: QObject(vehicle)
, _vehicle(vehicle)
, _mavlink(NULL)
......@@ -61,34 +67,34 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle)
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
// We signal this to ouselves in order to start timer on our thread
connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer);
connect(this, &ParameterManager::restartWaitingParamTimer, this, &ParameterManager::_restartWaitingParamTimer);
_initialRequestTimeoutTimer.setSingleShot(true);
_initialRequestTimeoutTimer.setInterval(6000);
connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_initialRequestTimeout);
connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout);
_waitingParamTimeoutTimer.setSingleShot(true);
_waitingParamTimeoutTimer.setInterval(1000);
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterLoader::_waitingParamTimeout);
connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterLoader::_parameterUpdate);
connect(_vehicle->uas(), &UASInterface::parameterUpdate, this, &ParameterManager::_parameterUpdate);
_versionParam = vehicle->firmwarePlugin()->getVersionParam();
_defaultComponentIdParam = vehicle->firmwarePlugin()->getDefaultComponentIdParam();
qCDebug(ParameterLoaderLog) << "Default component param" << _defaultComponentIdParam;
qCDebug(ParameterManagerLog) << "Default component param" << _defaultComponentIdParam;
// Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
refreshAllParameters();
}
ParameterLoader::~ParameterLoader()
ParameterManager::~ParameterManager()
{
delete _parameterMetaData;
}
/// Called whenever a parameter is updated or first seen.
void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
void ParameterManager::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value)
{
// Is this for our uas?
if (uasId != _vehicle->id()) {
......@@ -98,7 +104,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_initialRequestTimeoutTimer.stop();
if (_initialLoadComplete) {
qCDebug(ParameterLoaderLog) << "_parameterUpdate (id:" << uasId <<
qCDebug(ParameterManagerLog) << "_parameterUpdate (id:" << uasId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
......@@ -108,7 +114,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
")";
} else {
// This is too noisy during initial load
qCDebug(ParameterLoaderVerboseLog) << "_parameterUpdate (id:" << uasId <<
qCDebug(ParameterManagerVerboseLog) << "_parameterUpdate (id:" << uasId <<
"componentId:" << componentId <<
"name:" << parameterName <<
"count:" << parameterCount <<
......@@ -122,7 +128,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
// Handy for testing retry logic
static int counter = 0;
if (counter++ & 0x8) {
qCDebug(ParameterLoaderLog) << "Artificial discard" << counter;
qCDebug(ParameterManagerLog) << "Artificial discard" << counter;
return;
}
#endif
......@@ -161,12 +167,12 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_waitingReadParamNameMap[componentId] = QMap<QString, int>();
_waitingWriteParamNameMap[componentId] = QMap<QString, int>();
qCDebug(ParameterLoaderLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
qCDebug(ParameterManagerLog) << "Seeing component for first time, id:" << componentId << "parameter count:" << parameterCount;
}
// Determine default component id
if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) {
qCDebug(ParameterLoaderLog) << "Default component id determined" << componentId;
qCDebug(ParameterManagerLog) << "Default component id determined" << componentId;
_defaultComponentId = componentId;
}
......@@ -188,9 +194,9 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_waitingReadParamIndexMap[componentId].remove(parameterId);
_waitingReadParamNameMap[componentId].remove(parameterName);
_waitingWriteParamNameMap[componentId].remove(parameterName);
qCDebug(ParameterLoaderVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
qCDebug(ParameterLoaderLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
qCDebug(ParameterLoaderLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
qCDebug(ParameterManagerVerboseLog) << "_waitingReadParamIndexMap:" << _waitingReadParamIndexMap[componentId];
qCDebug(ParameterManagerLog) << "_waitingReadParamNameMap" << _waitingReadParamNameMap[componentId];
qCDebug(ParameterManagerLog) << "_waitingWriteParamNameMap" << _waitingWriteParamNameMap[componentId];
// Track how many parameters we are still waiting for
......@@ -202,7 +208,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
}
if (waitingReadParamIndexCount) {
qCDebug(ParameterLoaderLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
qCDebug(ParameterManagerLog) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
}
......@@ -210,20 +216,20 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
waitingReadParamNameCount += _waitingReadParamNameMap[waitingComponentId].count();
}
if (waitingReadParamNameCount) {
qCDebug(ParameterLoaderLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
qCDebug(ParameterManagerLog) << "waitingReadParamNameCount:" << waitingReadParamNameCount;
}
foreach(int waitingComponentId, _waitingWriteParamNameMap.keys()) {
waitingWriteParamNameCount += _waitingWriteParamNameMap[waitingComponentId].count();
}
if (waitingWriteParamNameCount) {
qCDebug(ParameterLoaderLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
qCDebug(ParameterManagerLog) << "waitingWriteParamNameCount:" << waitingWriteParamNameCount;
}
int readWaitingParamCount = waitingReadParamIndexCount + waitingReadParamNameCount;
int totalWaitingParamCount = readWaitingParamCount + waitingWriteParamNameCount;
if (totalWaitingParamCount) {
qCDebug(ParameterLoaderLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
qCDebug(ParameterManagerLog) << "totalWaitingParamCount:" << totalWaitingParamCount;
} else if (_defaultComponentId != MAV_COMP_ID_ALL) {
// No more parameters to wait for, stop the timeout. Be careful to not stop timer if we don't have the default
// component yet.
......@@ -247,7 +253,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
}
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
qCDebug(ParameterLoaderLog) << "Adding new fact";
qCDebug(ParameterManagerLog) << "Adding new fact";
FactMetaData::ValueType_t factType;
switch (mavType) {
......@@ -286,7 +292,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
_mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
// We need to know when the fact changes from QML so that we can send the new value to the parameter manager
connect(fact, &Fact::_containerRawValueChanged, this, &ParameterLoader::_valueUpdated);
connect(fact, &Fact::_containerRawValueChanged, this, &ParameterManager::_valueUpdated);
}
_dataMutex.unlock();
......@@ -336,7 +342,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param
/// Connected to Fact::valueUpdated
///
/// Writes the parameter to mavlink, sets up for write wait
void ParameterLoader::_valueUpdated(const QVariant& value)
void ParameterManager::_valueUpdated(const QVariant& value)
{
Fact* fact = qobject_cast<Fact*>(sender());
Q_ASSERT(fact);
......@@ -355,14 +361,14 @@ void ParameterLoader::_valueUpdated(const QVariant& value)
_dataMutex.unlock();
_writeParameterRaw(componentId, fact->name(), value);
qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
qCDebug(ParameterManagerLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")";
if (fact->rebootRequired() && !qgcApp()->runningUnitTests()) {
qgcApp()->showMessage(QStringLiteral("Change of parameter %1 requires a Vehicle reboot to take effect").arg(name));
}
}
void ParameterLoader::refreshAllParameters(uint8_t componentID)
void ParameterManager::refreshAllParameters(uint8_t componentID)
{
_dataMutex.lock();
......@@ -391,10 +397,10 @@ void ParameterLoader::refreshAllParameters(uint8_t componentID)
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID);
qCDebug(ParameterLoaderLog) << "Request to refresh all parameters for component ID:" << what;
qCDebug(ParameterManagerLog) << "Request to refresh all parameters for component ID:" << what;
}
void ParameterLoader::_determineDefaultComponentId(void)
void ParameterManager::_determineDefaultComponentId(void)
{
if (_defaultComponentId == MAV_COMP_ID_ALL) {
// We don't have a default component id yet. That means the plugin can't provide
......@@ -417,7 +423,7 @@ void ParameterLoader::_determineDefaultComponentId(void)
}
/// Translates FactSystem::defaultComponentId to real component id if needed
int ParameterLoader::_actualComponentId(int componentId)
int ParameterManager::_actualComponentId(int componentId)
{
if (componentId == FactSystem::defaultComponentId) {
componentId = _defaultComponentId;
......@@ -429,10 +435,10 @@ int ParameterLoader::_actualComponentId(int componentId)
return componentId;
}
void ParameterLoader::refreshParameter(int componentId, const QString& name)
void ParameterManager::refreshParameter(int componentId, const QString& name)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterLoaderLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
qCDebug(ParameterManagerLog) << "refreshParameter (component id:" << componentId << "name:" << name << ")";
_dataMutex.lock();
......@@ -451,10 +457,10 @@ void ParameterLoader::refreshParameter(int componentId, const QString& name)
_readParameterRaw(componentId, name, -1);
}
void ParameterLoader::refreshParametersPrefix(int componentId, const QString& namePrefix)
void ParameterManager::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
componentId = _actualComponentId(componentId);
qCDebug(ParameterLoaderLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";
qCDebug(ParameterManagerLog) << "refreshParametersPrefix (component id:" << componentId << "name:" << namePrefix << ")";
foreach(const QString &name, _mapParameterName2Variant[componentId].keys()) {
if (name.startsWith(namePrefix)) {
......@@ -463,7 +469,7 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na
}
}
bool ParameterLoader::parameterExists(int componentId, const QString& name)
bool ParameterManager::parameterExists(int componentId, const QString& name)
{
bool ret = false;
......@@ -475,7 +481,7 @@ bool ParameterLoader::parameterExists(int componentId, const QString& name)
return ret;
}
Fact* ParameterLoader::getFact(int componentId, const QString& name)
Fact* ParameterManager::getFact(int componentId, const QString& name)
{
componentId = _actualComponentId(componentId);
......@@ -488,7 +494,7 @@ Fact* ParameterLoader::getFact(int componentId, const QString& name)
return _mapParameterName2Variant[componentId][mappedParamName].value<Fact*>();
}
QStringList ParameterLoader::parameterNames(int componentId)
QStringList ParameterManager::parameterNames(int componentId)
{
QStringList names;
......@@ -499,7 +505,7 @@ QStringList ParameterLoader::parameterNames(int componentId)
return names;
}
void ParameterLoader::_setupGroupMap(void)
void ParameterManager::_setupGroupMap(void)
{
// Must be able to handle being called multiple times
_mapGroup2ParameterName.clear();
......@@ -512,12 +518,12 @@ void ParameterLoader::_setupGroupMap(void)
}
}
const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
const QMap<int, QMap<QString, QStringList> >& ParameterManager::getGroupMap(void)
{
return _mapGroup2ParameterName;
}
void ParameterLoader::_waitingParamTimeout(void)
void ParameterManager::_waitingParamTimeout(void)
{
bool paramsRequested = false;
const int maxBatchSize = 10;
......@@ -531,13 +537,13 @@ void ParameterLoader::_waitingParamTimeout(void)
if (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam) {
// Give up on this index
_failedReadParamIndexMap[componentId] << paramIndex;
qCDebug(ParameterLoaderLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
qCDebug(ParameterManagerLog) << "Giving up on (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
_waitingReadParamIndexMap[componentId].remove(paramIndex);
} else {
// Retry again
paramsRequested = true;
_readParameterRaw(componentId, "", paramIndex);
qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
......@@ -565,7 +571,7 @@ void ParameterLoader::_waitingParamTimeout(void)
_waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue());
qCDebug(ParameterLoaderLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
qCDebug(ParameterManagerLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
......@@ -585,7 +591,7 @@ void ParameterLoader::_waitingParamTimeout(void)
_waitingReadParamNameMap[componentId][paramName]++; // Bump retry count
if (_waitingReadParamNameMap[componentId][paramName] <= _maxReadWriteRetry) {
_readParameterRaw(componentId, paramName, -1);
qCDebug(ParameterLoaderLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
qCDebug(ParameterManagerLog) << "Read re-request for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingReadParamNameMap[componentId][paramName] << ")";
if (++batchCount > maxBatchSize) {
goto Out;
}
......@@ -604,7 +610,7 @@ Out:
}
}
void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
void ParameterManager::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
{
mavlink_message_t msg;
char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];
......@@ -620,7 +626,7 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
void ParameterManager::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
{
mavlink_param_set_t p;
mavlink_param_union_t union_value;
......@@ -673,7 +679,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
void ParameterManager::_writeLocalParamCache(int uasId, int componentId)
{
MapID2NamedParam cache_map;
......@@ -690,18 +696,18 @@ void ParameterLoader::_writeLocalParamCache(int uasId, int componentId)
ds << cache_map;
}
QDir ParameterLoader::parameterCacheDir()
QDir ParameterManager::parameterCacheDir()
{
const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
return spath + QDir::separator() + "ParamCache";
}
QString ParameterLoader::parameterCacheFile(int uasId, int componentId)
QString ParameterManager::parameterCacheFile(int uasId, int componentId)
{
return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId));
}
void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
void ParameterManager::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value)
{
uint32_t crc32_value = 0;
/* The datastructure of the cache table */
......@@ -728,7 +734,7 @@ void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant has
}
if (crc32_value == hash_value.toUInt()) {
qCInfo(ParameterLoaderLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath());
/* if the two param set hashes match, just load from the disk */
int count = cache_map.count();
foreach(int id, cache_map.keys()) {
......@@ -773,7 +779,7 @@ void ParameterLoader::_tryCacheHashLoad(int uasId, int componentId, QVariant has
}
}
void ParameterLoader::_saveToEEPROM(void)
void ParameterManager::_saveToEEPROM(void)
{
if (_saveRequired) {
_saveRequired = false;
......@@ -781,14 +787,14 @@ void ParameterLoader::_saveToEEPROM(void)
mavlink_message_t msg;
mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
qCDebug(ParameterManagerLog) << "_saveToEEPROM";
} else {
qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
qCDebug(ParameterManagerLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
}
}
}
QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QString ParameterManager::readParametersFromStream(QTextStream& stream)
{
QString errors;
......@@ -811,7 +817,7 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QString error;
error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName);
errors += error;
qCDebug(ParameterLoaderLog) << error;
qCDebug(ParameterManagerLog) << error;
continue;
}
......@@ -820,11 +826,11 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QString error;
error = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType));
errors += error;
qCDebug(ParameterLoaderLog) << error;
qCDebug(ParameterManagerLog) << error;
continue;
}
qCDebug(ParameterLoaderLog) << "Updating parameter" << componentId << paramName << valStr;
qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
fact->setRawValue(valStr);
}
}
......@@ -833,7 +839,7 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
return errors;
}
void ParameterLoader::writeParametersToStream(QTextStream &stream)
void ParameterManager::writeParametersToStream(QTextStream &stream)
{
stream << "# Onboard parameters for vehicle " << _vehicle->id() << "\n";
stream << "#\n";
......@@ -853,7 +859,7 @@ void ParameterLoader::writeParametersToStream(QTextStream &stream)
stream.flush();
}
MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t factType)
MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType)
{
switch (factType) {
case FactMetaData::valueTypeUint8:
......@@ -883,7 +889,7 @@ MAV_PARAM_TYPE ParameterLoader::_factTypeToMavType(FactMetaData::ValueType_t fac
}
}
FactMetaData::ValueType_t ParameterLoader::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType)
{
switch (mavType) {
case MAV_PARAM_TYPE_UINT8:
......@@ -913,12 +919,12 @@ FactMetaData::ValueType_t ParameterLoader::_mavTypeToFactType(MAV_PARAM_TYPE mav
}
}
void ParameterLoader::_restartWaitingParamTimer(void)
void ParameterManager::_restartWaitingParamTimer(void)
{
_waitingParamTimeoutTimer.start();
}
void ParameterLoader::_addMetaDataToDefaultComponent(void)
void ParameterManager::_addMetaDataToDefaultComponent(void)
{
if (_defaultComponentId == MAV_COMP_ID_ALL) {
// We don't know what the default component is so we can't support meta data
......@@ -935,11 +941,11 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void)
// Parameter versioning is still not really figured out correctly. We need to handle ArduPilot specially based on vehicle version.
// The current three version are hardcoded in.
metaDataFile = ((APMFirmwarePlugin*)_vehicle->firmwarePlugin())->getParameterMetaDataFile(_vehicle);
qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile;
qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile;
} else {
// Load best parameter meta data set
metaDataFile = parameterMetaDataFile(_vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
qCDebug(ParameterLoaderLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion;
}
_parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
......@@ -952,7 +958,7 @@ void ParameterLoader::_addMetaDataToDefaultComponent(void)
}
/// @param failIfNoDefaultComponent true: Fails parameter load if no default component but we should have one
void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
{
// Already processed?
if (_initialLoadComplete) {
......@@ -984,7 +990,7 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
}
indexList += QString("%1").arg(paramIndex);
initialLoadFailures = true;
qCDebug(ParameterLoaderLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
qCDebug(ParameterManagerLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")";
}
}
if (initialLoadFailures) {
......@@ -993,7 +999,7 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterLoaderLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
qCWarning(ParameterManagerLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList;
}
emit parametersReady(true /* missingParameters */);
return;
......@@ -1006,7 +1012,7 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
"If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
"If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.");
if (!qgcApp()->runningUnitTests()) {
qCWarning(ParameterLoaderLog) << "Default component was never found, param:" << _defaultComponentIdParam;
qCWarning(ParameterManagerLog) << "Default component was never found, param:" << _defaultComponentIdParam;
}
emit parametersReady(true /* missingParameters */);
return;
......@@ -1018,7 +1024,7 @@ void ParameterLoader::_checkInitialLoadComplete(bool failIfNoDefaultComponent)
emit parametersReady(false /* no missingParameters */);
}
void ParameterLoader::_initialRequestTimeout(void)
void ParameterManager::_initialRequestTimeout(void)
{
if (!_vehicle->genericFirmware()) {
// Generic vehicles (like BeBop) may not have any parameters, so don't annoy the user
......@@ -1030,7 +1036,7 @@ void ParameterLoader::_initialRequestTimeout(void)
}
}
QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
QString ParameterManager::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion)
{
bool cacheHit = false;
FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
......@@ -1047,7 +1053,7 @@ QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int w
if (wantedMajorVersion != cacheMajorVersion) {
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion;
} else {
qCDebug(ParameterLoaderLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion;
cacheHit = true;
}
}
......@@ -1080,7 +1086,7 @@ QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int w
qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion;
cacheHit = false;
} else {
qCDebug(ParameterLoaderLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion;
cacheHit = true;
}
}
......@@ -1089,7 +1095,7 @@ QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int w
int internalMinorVersion, internalMajorVersion;
QString internalMetaDataFile = plugin->internalParameterMetaDataFile();
plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion);
qCDebug(ParameterLoaderLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion;
if (cacheHit) {
// Cache hit is available, we need to check if internal meta data is a better match, if so use internal version
if (internalMajorVersion == wantedMajorVersion) {
......@@ -1121,23 +1127,23 @@ QString ParameterLoader::parameterMetaDataFile(MAV_AUTOPILOT firmwareType, int w
minorVersion = internalMinorVersion;
metaDataFile = internalMetaDataFile;
}
qCDebug(ParameterLoaderLog) << "ParameterLoader::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion;
return metaDataFile;
}
void ParameterLoader::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType)
{
FirmwarePlugin* plugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
int newMajorVersion, newMinorVersion;
plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion);
qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion;
// Find the cache hit closest to this new file
int cacheMajorVersion, cacheMinorVersion;
QString cacheHit = ParameterLoader::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
QString cacheHit = ParameterManager::parameterMetaDataFile(firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
bool cacheNewFile = false;
if (cacheHit.isEmpty()) {
......@@ -1162,14 +1168,14 @@ void ParameterLoader::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPIL
QSettings settings;
QDir cacheDir = QFileInfo(settings.fileName()).dir();
QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion)));
qCDebug(ParameterLoaderLog) << "ParameterLoader::cacheMetaDataFile caching file:" << cacheFile.fileName();
qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName();
QFile newFile(metaDataFile);
newFile.copy(cacheFile.fileName());
}
}
/// Remap a parameter from one firmware version to another
QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
QString ParameterManager::_remapParamNameToVersion(const QString& paramName)
{
QString mappedParamName;
......@@ -1181,7 +1187,7 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
int majorVersion = _vehicle->firmwareMajorVersion();
int minorVersion = _vehicle->firmwareMinorVersion();
qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
mappedParamName = paramName.right(paramName.count() - 2);
......@@ -1194,7 +1200,7 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
if (!majorVersionRemap.contains(majorVersion)) {
// No mapping for this major version
qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion: no major version mapping";
qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
return mappedParamName;
}
......@@ -1208,7 +1214,7 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
if (remap.contains(mappedParamName)) {
QString toParamName = remap[mappedParamName];
qCDebug(ParameterLoaderLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to"<< currentMinorVersion << mappedParamName << toParamName;
mappedParamName = toParamName;
}
}
......@@ -1218,7 +1224,7 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName)
}
/// The offline editing vehicle can have custom loaded params bolted into it.
void ParameterLoader::_loadOfflineEditingParams(void)
void ParameterManager::_loadOfflineEditingParams(void)
{
QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
if (paramFilename.isEmpty()) {
......@@ -1227,7 +1233,7 @@ void ParameterLoader::_loadOfflineEditingParams(void)
QFile paramFile(paramFilename);
if (!paramFile.open(QFile::ReadOnly)) {
qCWarning(ParameterLoaderLog) << "Unable to open offline editing params file" << paramFilename;
qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
}
QTextStream paramStream(&paramFile);
......@@ -1281,6 +1287,113 @@ void ParameterLoader::_loadOfflineEditingParams(void)
}
_addMetaDataToDefaultComponent();
_setupGroupMap();
_parametersReady = true;
_initialLoadComplete = true;
}
void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject)
{
QList<int> rgCompIds;
QStringList rgParamNames;
if (componentId == MAV_COMP_ID_ALL) {
rgCompIds = _mapParameterName2Variant.keys();
} else {
rgCompIds.append(_actualComponentId(componentId));
}
QJsonArray rgParams;
// Loop over all requested component ids
for (int i=0; i<rgCompIds.count(); i++) {
int compId = rgCompIds[i];
if (!_mapParameterName2Variant.contains(compId)) {
qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson no params for compId" << compId;
continue;
}
// Build list of parameter names if not specified
if (paramsToSave.count() == 0) {
rgParamNames = parameterNames(compId);
} else {
rgParamNames = paramsToSave;
}
// Loop over parameter names adding each to json array
for (int j=0; j<rgParamNames.count(); j++) {
QString paramName = rgParamNames[j];
if (!parameterExists(compId, paramName)) {
qCDebug(ParameterManagerLog) << "ParameterManager::saveToJson param not found compId:param" << compId << paramName;
continue;
}
QJsonObject paramJson;
Fact* fact = getFact(compId, paramName);
paramJson.insert(_jsonCompIdKey, QJsonValue(compId));
paramJson.insert(_jsonParamNameKey, QJsonValue(fact->name()));
paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble()));
rgParams.append(QJsonValue(paramJson));
}
}
saveObject.insert(_jsonParametersKey, QJsonValue(rgParams));
}
bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
QList<QJsonValue::Type> keyTypes;
errorString.clear();
if (required) {
if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonParametersKey), errorString)) {
return false;
}
} else if (!json.contains(_jsonParametersKey)) {
return true;
}
keyTypes = { QJsonValue::Array };
if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonParametersKey), keyTypes, errorString)) {
return false;
}
QJsonArray rgParams = json[_jsonParametersKey].toArray();
for (int i=0; i<rgParams.count(); i++) {
QJsonValueRef paramValue = rgParams[i];
if (!paramValue.isObject()) {
errorString = tr("%1 key is not a json object").arg(_jsonParametersKey);
return false;
}
QJsonObject param = paramValue.toObject();
QStringList requiredKeys = { _jsonCompIdKey, _jsonParamNameKey, _jsonParamValueKey };
if (!JsonHelper::validateRequiredKeys(param, requiredKeys, errorString)) {
return false;
}
keyTypes = { QJsonValue::Double, QJsonValue::String, QJsonValue::Double };
if (!JsonHelper::validateKeyTypes(param, requiredKeys, keyTypes, errorString)) {
return false;
}
int compId = param[_jsonCompIdKey].toInt();
QString name = param[_jsonParamNameKey].toString();
double value = param[_jsonParamValueKey].toDouble();
if (!parameterExists(compId, name)) {
qCDebug(ParameterManagerLog) << "ParameterManager::loadFromJson param not found compId:param" << compId << name;
continue;
}
Fact* fact = getFact(compId, name);
fact->setRawValue(value);
}
return true;
}
......@@ -8,8 +8,8 @@
****************************************************************************/
#ifndef PARAMETERLOADER_H
#define PARAMETERLOADER_H
#ifndef ParameterManager_H
#define ParameterManager_H
#include <QObject>
#include <QMap>
......@@ -17,6 +17,7 @@
#include <QLoggingCategory>
#include <QMutex>
#include <QDir>
#include <QJsonObject>
#include "FactSystem.h"
#include "MAVLinkProtocol.h"
......@@ -27,18 +28,18 @@
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerboseLog)
/// Connects to Parameter Manager to load/update Facts
class ParameterLoader : public QObject
class ParameterManager : public QObject
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
ParameterLoader(Vehicle* vehicle);
ParameterManager(Vehicle* vehicle);
~ParameterLoader();
~ParameterManager();
/// @return Directory of parameter caches
static QDir parameterCacheDir();
......@@ -91,8 +92,21 @@ public:
/// 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);
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:
/// Signalled when the full set of facts are ready
void parametersReady(bool missingParameters);
......@@ -179,6 +193,10 @@ private:
static Fact _defaultFact; ///< Used to return default fact, when parameter not found
static const char* _cachedMetaDataFilePrefix;
static const char* _jsonParametersKey;
static const char* _jsonCompIdKey;
static const char* _jsonParamNameKey;
static const char* _jsonParamValueKey;
};
#endif
......@@ -8,13 +8,13 @@
****************************************************************************/
#include "ParameterLoaderTest.h"
#include "ParameterManagerTest.h"
#include "MultiVehicleManager.h"
#include "QGCApplication.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
/// 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);
_mockLink = MockLink::startPX4MockLink(false, failureMode);
......@@ -34,7 +34,7 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail
QVERIFY(vehicle);
// 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);
arguments = spyProgress.takeFirst();
QCOMPARE(arguments.count(), 1);
......@@ -54,18 +54,18 @@ void ParameterLoaderTest::_noFailureWorker(MockConfiguration::FailureMode_t fail
}
void ParameterLoaderTest::_noFailure(void)
void ParameterManagerTest::_noFailure(void)
{
_noFailureWorker(MockConfiguration::FailNone);
}
void ParameterLoaderTest::_requestListMissingParamSuccess(void)
void ParameterManagerTest::_requestListMissingParamSuccess(void)
{
_noFailureWorker(MockConfiguration::FailMissingParamOnInitialReqest);
}
// Test no response to param_request_list
void ParameterLoaderTest::_requestListNoResponse(void)
void ParameterManagerTest::_requestListNoResponse(void)
{
Q_ASSERT(!_mockLink);
_mockLink = MockLink::startPX4MockLink(false, MockConfiguration::FailParamNoReponseToRequestList);
......@@ -85,7 +85,7 @@ void ParameterLoaderTest::_requestListNoResponse(void)
QVERIFY(vehicle);
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
QCOMPARE(spyProgress.wait(500), false);
......@@ -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
// param_read requests.
void ParameterLoaderTest::_requestListMissingParamFail(void)
void ParameterManagerTest::_requestListMissingParamFail(void)
{
// Will pop error about missing params
setExpectedMessageBox(QMessageBox::Ok);
......@@ -120,7 +120,7 @@ void ParameterLoaderTest::_requestListMissingParamFail(void)
QVERIFY(vehicle);
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
QCOMPARE(spyProgress.wait(2000), true);
......
......@@ -8,15 +8,15 @@
****************************************************************************/
#ifndef ParameterLoaderTest_H
#define ParameterLoaderTest_H
#ifndef ParameterManagerTest_H
#define ParameterManagerTest_H
#include "UnitTest.h"
#include "MockLink.h"
#include "MultiSignalSpy.h"
#include "MockLink.h"
class ParameterLoaderTest : public UnitTest
class ParameterManagerTest : public UnitTest
{
Q_OBJECT
......
......@@ -12,7 +12,7 @@
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
const char* APMGeoFenceManager::_fenceTotalParam = "FENCE_TOTAL";
const char* APMGeoFenceManager::_fenceActionParam = "FENCE_ACTION";
......@@ -30,9 +30,9 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
, _fenceTypeFact(NULL)
{
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();
}
}
......
......@@ -15,7 +15,7 @@
#define PX4FirmwarePlugin_H
#include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "PX4ParameterMetaData.h"
#include "PX4GeoFenceManager.h"
......@@ -57,6 +57,7 @@ public:
QObject* loadParameterMetaData (const QString& metaDataFile);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message);
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
// names may change.
......
......@@ -10,14 +10,14 @@
#include "PX4GeoFenceManager.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle)
, _firstParamLoadComplete(false)
, _circleRadiusFact(NULL)
{
connect(_vehicle->getParameterLoader(), &ParameterLoader::parametersReady, this, &PX4GeoFenceManager::_parametersReady);
connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &PX4GeoFenceManager::_parametersReady);
}
PX4GeoFenceManager::~PX4GeoFenceManager()
......
......@@ -64,7 +64,7 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaDataFile)
{
qCDebug(ParameterLoaderLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile;
qCDebug(ParameterManagerLog) << "PX4ParameterMetaData::loadParameterFactMetaDataFile" << metaDataFile;
if (_parameterMetaDataLoaded) {
qWarning() << "Internal error: parameter meta data loaded more than once";
......
......@@ -20,7 +20,7 @@ QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGC_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog, "FirmwareUpgradeVerboseLog")
QGC_LOGGING_CATEGORY(MissionCommandsLog, "MissionCommandsLog")
QGC_LOGGING_CATEGORY(MissionItemLog, "MissionItemLog")
QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog")
QGC_LOGGING_CATEGORY(ParameterManagerLog, "ParameterManagerLog")
QGCLoggingCategoryRegister* _instance = NULL;
const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters";
......
......@@ -22,7 +22,7 @@ Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeVerboseLog)
Q_DECLARE_LOGGING_CATEGORY(MissionCommandsLog)
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterLoaderLog)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
......
......@@ -14,6 +14,7 @@
#include "ParameterEditorController.h"
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include "ParameterManager.h"
#ifndef __mobile__
#include "QGCFileDialog.h"
......@@ -28,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void)
: _currentComponentId(_vehicle->defaultComponentId())
, _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()) {
_componentIds += QString("%1").arg(componentId);
}
......@@ -48,14 +49,14 @@ ParameterEditorController::~ParameterEditorController()
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();
}
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];
}
......@@ -187,7 +188,7 @@ void ParameterEditorController::_updateParameters(void)
QObjectList newParameterList;
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]) {
newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter));
}
......
......@@ -18,7 +18,7 @@
#include "JoystickManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include "QGCApplication.h"
#include "QGCImageProvider.h"
#include "GAudioOutput.h"
......@@ -199,11 +199,11 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable);
_parameterLoader = new ParameterLoader(this);
connect(_parameterLoader, &ParameterLoader::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks);
connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
_parameterLoader = new ParameterManager(this);
connect(_parameterLoader, &ParameterManager::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks);
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);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
......@@ -332,9 +332,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_missionManager = new MissionManager(this);
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);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
......@@ -1813,7 +1813,7 @@ void Vehicle::rebootVehicle()
int Vehicle::defaultComponentId(void)
{
return _parameterLoader->defaultComponenentId();
return _parameterLoader->defaultComponentId();
}
void Vehicle::setSoloFirmware(bool soloFirmware)
......@@ -1835,7 +1835,7 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
/// Returns true if the specifed parameter exists from the default component
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
......@@ -1843,7 +1843,7 @@ bool Vehicle::parameterExists(int componentId, const QString& name) const
/// parameterExists.
Fact* Vehicle::getParameterFact(int componentId, const QString& name)
{
return getParameterLoader()->getFact(componentId, name);
return getParameterManager()->getFact(componentId, name);
}
void Vehicle::_newMissionItemsAvailable(void)
......
......@@ -34,7 +34,7 @@ class AutoPilotPlugin;
class AutoPilotPluginManager;
class MissionManager;
class GeoFenceManager;
class ParameterLoader;
class ParameterManager;
class JoystickManager;
class UASMessage;
......@@ -544,8 +544,8 @@ public:
void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterLoader* getParameterLoader(void) { return _parameterLoader; }
ParameterLoader* getParameterLoader(void) const { return _parameterLoader; }
ParameterManager* getParameterManager(void) { return _parameterLoader; }
ParameterManager* getParameterManager(void) const { return _parameterLoader; }
static const int cMaxRcChannels = 18;
......@@ -763,7 +763,7 @@ private:
GeoFenceManager* _geoFenceManager;
bool _geoFenceManagerInitialRequestComplete;
ParameterLoader* _parameterLoader;
ParameterManager* _parameterLoader;
bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT
......
......@@ -18,7 +18,7 @@
#include "QGCMAVLink.h"
#include "QGCApplication.h"
#include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include "ParameterManager.h"
#include <QDebug>
#include <QFile>
......@@ -275,7 +275,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
}
// Cache this file with the system
ParameterLoader::cacheMetaDataFile(parameterFilename, firmwareType);
ParameterManager::cacheMetaDataFile(parameterFilename, firmwareType);
}
// Decompress the airframe xml and save to file
......
......@@ -29,7 +29,7 @@
#include "MainWindowTest.h"
#include "FileManagerTest.h"
#include "TCPLinkTest.h"
#include "ParameterLoaderTest.h"
#include "ParameterManagerTest.h"
#include "MissionCommandTreeTest.h"
#include "LogDownloadTest.h"
......@@ -49,7 +49,7 @@ UT_REGISTER_TEST(MissionManagerTest)
UT_REGISTER_TEST(RadioConfigTest)
UT_REGISTER_TEST(TCPLinkTest)
UT_REGISTER_TEST(FileManagerTest)
UT_REGISTER_TEST(ParameterLoaderTest)
UT_REGISTER_TEST(ParameterManagerTest)
UT_REGISTER_TEST(MissionCommandTreeTest)
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