Unverified Commit d3e68285 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6004 from DonLakeFlyer/VolatileFacts

Add support for volatile Facts/Parameters
parents d7790dd9 e9505588
...@@ -662,3 +662,13 @@ bool Fact::readOnly(void) const ...@@ -662,3 +662,13 @@ bool Fact::readOnly(void) const
return false; return false;
} }
} }
bool Fact::volatileValue(void) const
{
if (_metaData) {
return _metaData->volatileValue();
} else {
qWarning() << kMissingMetadata << name();
return false;
}
}
...@@ -71,6 +71,7 @@ public: ...@@ -71,6 +71,7 @@ public:
Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT) Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT)
Q_PROPERTY(bool hasControl READ hasControl CONSTANT) Q_PROPERTY(bool hasControl READ hasControl CONSTANT)
Q_PROPERTY(bool readOnly READ readOnly CONSTANT) Q_PROPERTY(bool readOnly READ readOnly CONSTANT)
Q_PROPERTY(bool volatileValue READ volatileValue CONSTANT)
/// Convert and validate value /// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well /// @param convertOnly true: validate type conversion only, false: validate against meta data as well
...@@ -118,6 +119,7 @@ public: ...@@ -118,6 +119,7 @@ public:
bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; } bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; }
bool hasControl (void) const; bool hasControl (void) const;
bool readOnly (void) const; bool readOnly (void) const;
bool volatileValue (void) const;
/// Returns the values as a string with full 18 digit precision if float/double. /// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const; QString rawValueStringFullPrecision(void) const;
......
...@@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent) ...@@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _increment (std::numeric_limits<double>::quiet_NaN()) , _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
, _volatile (false)
{ {
_category = kDefaultCategory; _category = kDefaultCategory;
_group = kDefaultGroup; _group = kDefaultGroup;
...@@ -115,6 +116,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) ...@@ -115,6 +116,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _increment (std::numeric_limits<double>::quiet_NaN()) , _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
, _volatile (false)
{ {
_category = kDefaultCategory; _category = kDefaultCategory;
_group = kDefaultGroup; _group = kDefaultGroup;
...@@ -143,6 +145,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent ...@@ -143,6 +145,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
, _increment (std::numeric_limits<double>::quiet_NaN()) , _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true) , _hasControl (true)
, _readOnly (false) , _readOnly (false)
, _volatile (false)
{ {
_category = kDefaultCategory; _category = kDefaultCategory;
_group = kDefaultGroup; _group = kDefaultGroup;
...@@ -175,6 +178,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) ...@@ -175,6 +178,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_increment = other._increment; _increment = other._increment;
_hasControl = other._hasControl; _hasControl = other._hasControl;
_readOnly = other._readOnly; _readOnly = other._readOnly;
_volatile = other._volatile;
return *this; return *this;
} }
...@@ -1135,3 +1139,11 @@ QVariant FactMetaData::cookedMin(void) const ...@@ -1135,3 +1139,11 @@ QVariant FactMetaData::cookedMin(void) const
return cookedMin; return cookedMin;
} }
} }
void FactMetaData::setVolatileValue(bool bValue)
{
_volatile = bValue;
if (_volatile) {
_readOnly = true;
}
}
...@@ -104,6 +104,7 @@ public: ...@@ -104,6 +104,7 @@ public:
bool rebootRequired (void) const { return _rebootRequired; } bool rebootRequired (void) const { return _rebootRequired; }
bool hasControl (void) const { return _hasControl; } bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; } bool readOnly (void) const { return _readOnly; }
bool volatileValue (void) const { return _volatile; }
/// Amount to increment value when used in controls such as spin button or slider with detents. /// Amount to increment value when used in controls such as spin button or slider with detents.
/// NaN for no increment available. /// NaN for no increment available.
...@@ -134,6 +135,7 @@ public: ...@@ -134,6 +135,7 @@ public:
void setIncrement (double increment) { _increment = increment; } void setIncrement (double increment) { _increment = increment; }
void setHasControl (bool bValue) { _hasControl = bValue; } void setHasControl (bool bValue) { _hasControl = bValue; }
void setReadOnly (bool bValue) { _readOnly = bValue; } void setReadOnly (bool bValue) { _readOnly = bValue; }
void setVolatileValue (bool bValue);
void setTranslators(Translator rawTranslator, Translator cookedTranslator); void setTranslators(Translator rawTranslator, Translator cookedTranslator);
...@@ -239,6 +241,7 @@ private: ...@@ -239,6 +241,7 @@ private:
double _increment; double _increment;
bool _hasControl; bool _hasControl;
bool _readOnly; bool _readOnly;
bool _volatile;
// Exact conversion constants // Exact conversion constants
static const struct UnitConsts_s { static const struct UnitConsts_s {
......
...@@ -7,10 +7,6 @@ ...@@ -7,10 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterManager.h" #include "ParameterManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
...@@ -27,9 +23,8 @@ ...@@ -27,9 +23,8 @@
#include <QJsonArray> #include <QJsonArray>
/* types for local parameter cache */ /* types for local parameter cache */
typedef QPair<int, QVariant> ParamTypeVal; typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
typedef QPair<QString, ParamTypeVal> NamedParam; typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
typedef QMap<int, NamedParam> MapID2NamedParam;
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log") QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log") QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
...@@ -43,25 +38,26 @@ const char* ParameterManager::_jsonParamNameKey = "name"; ...@@ -43,25 +38,26 @@ const char* ParameterManager::_jsonParamNameKey = "name";
const char* ParameterManager::_jsonParamValueKey = "value"; const char* ParameterManager::_jsonParamValueKey = "value";
ParameterManager::ParameterManager(Vehicle* vehicle) ParameterManager::ParameterManager(Vehicle* vehicle)
: QObject(vehicle) : QObject (vehicle)
, _vehicle(vehicle) , _vehicle (vehicle)
, _mavlink(NULL) , _mavlink (NULL)
, _loadProgress(0.0) , _loadProgress (0.0)
, _parametersReady(false) , _parametersReady (false)
, _missingParameters(false) , _missingParameters (false)
, _initialLoadComplete(false) , _initialLoadComplete (false)
, _waitingForDefaultComponent(false) , _waitingForDefaultComponent (false)
, _saveRequired(false) , _saveRequired (false)
, _logReplay(vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay()) , _metaDataAddedToFacts (false)
, _parameterSetMajorVersion(-1) , _logReplay (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
, _parameterMetaData(NULL) , _parameterSetMajorVersion (-1)
, _prevWaitingReadParamIndexCount(0) , _parameterMetaData (NULL)
, _prevWaitingReadParamNameCount(0) , _prevWaitingReadParamIndexCount (0)
, _prevWaitingWriteParamNameCount(0) , _prevWaitingReadParamNameCount (0)
, _initialRequestRetryCount(0) , _prevWaitingWriteParamNameCount (0)
, _disableAllRetries(false) , _initialRequestRetryCount (0)
, _indexBatchQueueActive(false) , _disableAllRetries (false)
, _totalParamCount(0) , _indexBatchQueueActive (false)
, _totalParamCount (0)
{ {
_versionParam = vehicle->firmwarePlugin()->getVersionParam(); _versionParam = vehicle->firmwarePlugin()->getVersionParam();
...@@ -137,10 +133,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -137,10 +133,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
} }
#endif #endif
if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK" && !_logReplay) { if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
/* we received a cache hash, potentially load from cache */ if (!_initialLoadComplete && !_logReplay) {
_tryCacheHashLoad(vehicleId, componentId, value); /* we received a cache hash, potentially load from cache */
return; _tryCacheHashLoad(vehicleId, componentId, value);
}
return;
} }
_initialRequestTimeoutTimer.stop(); _initialRequestTimeoutTimer.stop();
...@@ -154,8 +152,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString ...@@ -154,8 +152,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_totalParamCount += parameterCount; _totalParamCount += parameterCount;
} }
_mapParameterId2Name[componentId][parameterId] = parameterName;
// If we've never seen this component id before, setup the wait lists. // If we've never seen this component id before, setup the wait lists.
if (!_waitingReadParamIndexMap.contains(componentId)) { if (!_waitingReadParamIndexMap.contains(componentId)) {
// Add all indices to the wait list, parameter index is 0-based // Add all indices to the wait list, parameter index is 0-based
...@@ -735,19 +731,18 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN ...@@ -735,19 +731,18 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN
void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId) void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
{ {
MapID2NamedParam cache_map; CacheMapName2ParamTypeVal cacheMap;
foreach(int id, _mapParameterId2Name[componentId].keys()) { foreach(const QString& name, _mapParameterName2Variant[componentId].keys()) {
const QString name(_mapParameterId2Name[componentId][id]);
const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>(); const Fact *fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue())); cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue());
} }
QFile cache_file(parameterCacheFile(vehicleId, componentId)); QFile cacheFile(parameterCacheFile(vehicleId, componentId));
cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate); cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
QDataStream ds(&cache_file); QDataStream ds(&cacheFile);
ds << cache_map; ds << cacheMap;
} }
QDir ParameterManager::parameterCacheDir() QDir ParameterManager::parameterCacheDir()
...@@ -758,46 +753,70 @@ QDir ParameterManager::parameterCacheDir() ...@@ -758,46 +753,70 @@ QDir ParameterManager::parameterCacheDir()
QString ParameterManager::parameterCacheFile(int vehicleId, int componentId) QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
{ {
return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId)); return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId));
} }
void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value) void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value)
{ {
qCInfo(ParameterManagerLog) << "Attemping load from cache";
uint32_t crc32_value = 0; uint32_t crc32_value = 0;
/* The datastructure of the cache table */ /* The datastructure of the cache table */
MapID2NamedParam cache_map; CacheMapName2ParamTypeVal cacheMap;
QFile cache_file(parameterCacheFile(vehicleId, componentId)); QFile cacheFile(parameterCacheFile(vehicleId, componentId));
if (!cache_file.exists()) { if (!cacheFile.exists()) {
/* no local cache, just wait for them to come in*/ /* no local cache, just wait for them to come in*/
return; return;
} }
cache_file.open(QIODevice::ReadOnly); cacheFile.open(QIODevice::ReadOnly);
/* Deserialize the parameter cache table */ /* Deserialize the parameter cache table */
QDataStream ds(&cache_file); QDataStream ds(&cacheFile);
ds >> cache_map; ds >> cacheMap;
// Load parameter meta data for the version number stored in cache.
// We need meta data so we have access to the volatile bit
if (cacheMap.contains(_versionParam)) {
_parameterSetMajorVersion = cacheMap[_versionParam].second.toInt();
}
_loadMetaData();
/* compute the crc of the local cache to check against the remote */ /* compute the crc of the local cache to check against the remote */
foreach(int id, cache_map.keys()) { FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin();
const QString name(cache_map[id].first); foreach (const QString& name, cacheMap.keys()) {
const void *vdat = cache_map[id].second.second.constData(); bool volatileValue = false;
const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first);
crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(), crc32_value); FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType());
crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value); if (metaData) {
volatileValue = metaData->volatileValue();
}
if (volatileValue) {
// Does not take part in CRC
qCDebug(ParameterManagerLog) << "Volatile parameter" << name;
} else {
const ParamTypeVal& paramTypeVal = cacheMap[name];
const void *vdat = paramTypeVal.second.constData();
const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(), crc32_value);
crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value);
}
} }
/* if the two param set hashes match, just load from the disk */
if (crc32_value == hash_value.toUInt()) { if (crc32_value == hash_value.toUInt()) {
qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath()); qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
/* if the two param set hashes match, just load from the disk */
int count = cache_map.count(); int count = cacheMap.count();
foreach(int id, cache_map.keys()) { int index = 0;
const QString &name = cache_map[id].first; foreach (const QString& name, cacheMap.keys()) {
const QVariant &value = cache_map[id].second.second; const ParamTypeVal& paramTypeVal = cacheMap[name];
const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(cache_map[id].second.first); const FactMetaData::ValueType_t fact_type = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
const int mavType = _factTypeToMavType(fact_type); const int mavType = _factTypeToMavType(fact_type);
_parameterUpdate(vehicleId, componentId, name, count, id, mavType, value); _parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second);
} }
// Return the hash value to notify we don't want any more updates // Return the hash value to notify we don't want any more updates
mavlink_param_set_t p; mavlink_param_set_t p;
mavlink_param_union_t union_value; mavlink_param_union_t union_value;
...@@ -836,7 +855,10 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ...@@ -836,7 +855,10 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
ani->start(QAbstractAnimation::DeleteWhenStopped); ani->start(QAbstractAnimation::DeleteWhenStopped);
} else { } else {
qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cache_file).absoluteFilePath()); // Cache parameter version may differ from vehicle parameter version so we can't trust information loaded from cache parameter version number
_parameterSetMajorVersion = -1;
_clearMetaData();
qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
} }
} }
...@@ -993,7 +1015,15 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma ...@@ -993,7 +1015,15 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma
} }
} }
void ParameterManager::_addMetaDataToDefaultComponent(void) void ParameterManager::_clearMetaData(void)
{
if (_parameterMetaData) {
_parameterMetaData->deleteLater();
_parameterMetaData = NULL;
}
}
void ParameterManager::_loadMetaData(void)
{ {
if (_parameterMetaData) { if (_parameterMetaData) {
return; return;
...@@ -1004,9 +1034,18 @@ void ParameterManager::_addMetaDataToDefaultComponent(void) ...@@ -1004,9 +1034,18 @@ void ParameterManager::_addMetaDataToDefaultComponent(void)
// Load best parameter meta data set // Load best parameter meta data set
metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion);
qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion; qCDebug(ParameterManagerLog) << "Loading meta data file:major:minor" << metaDataFile << majorVersion << minorVersion;
_parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile);
}
void ParameterManager::_addMetaDataToDefaultComponent(void)
{
_loadMetaData();
if (_metaDataAddedToFacts) {
return;
}
_metaDataAddedToFacts = true;
// Loop over all parameters in default component adding meta data // Loop over all parameters in default component adding meta data
QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()]; QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()];
......
...@@ -142,6 +142,8 @@ private: ...@@ -142,6 +142,8 @@ private:
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int vehicleId, int componentId); void _writeLocalParamCache(int vehicleId, int componentId);
void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value); void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value);
void _loadMetaData(void);
void _clearMetaData(void);
void _addMetaDataToDefaultComponent(void); void _addMetaDataToDefaultComponent(void);
QString _remapParamNameToVersion(const QString& paramName); QString _remapParamNameToVersion(const QString& paramName);
void _loadOfflineEditingParams(void); void _loadOfflineEditingParams(void);
...@@ -158,8 +160,6 @@ private: ...@@ -158,8 +160,6 @@ private:
/// Second mapping is parameter name, to Fact* in QVariant /// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant; QMap<int, QVariantMap> _mapParameterName2Variant;
QMap<int, QMap<int, QString> > _mapParameterId2Name;
// Category map of default component parameters // Category map of default component parameters
QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _categoryMap; QMap<QString /* category */, QMap<QString /* group */, QStringList /* parameter names */> > _categoryMap;
...@@ -169,6 +169,7 @@ private: ...@@ -169,6 +169,7 @@ private:
bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not
bool _waitingForDefaultComponent; ///< true: last chance wait for default component params bool _waitingForDefaultComponent; ///< true: last chance wait for default component params
bool _saveRequired; ///< true: _saveToEEPROM should be called bool _saveRequired; ///< true: _saveToEEPROM should be called
bool _metaDataAddedToFacts; ///< true: FactMetaData has been adde to the default component facts
bool _logReplay; ///< true: running with log replay link bool _logReplay; ///< true: running with log replay link
QString _versionParam; ///< Parameter which contains parameter set version QString _versionParam; ///< Parameter which contains parameter set version
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
......
...@@ -218,6 +218,11 @@ public: ...@@ -218,6 +218,11 @@ public:
/// call deleteParameterMetaData when no longer needed. /// call deleteParameterMetaData when no longer needed.
virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; } virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; }
/// Returns the FactMetaData associated with the parameter name
/// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
/// @param name Parameter name
virtual FactMetaData* getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(name); Q_UNUSED(vehicleType); return NULL; }
/// Adds the parameter meta data to the Fact /// Adds the parameter meta data to the Fact
/// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; } virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; }
......
...@@ -247,6 +247,19 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) ...@@ -247,6 +247,19 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
return false; return false;
} }
FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType)
{
PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);
if (px4MetaData) {
return px4MetaData->getMetaDataForFact(name, vehicleType);
} else {
qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData";
}
return NULL;
}
void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
{ {
PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData); PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);
...@@ -258,6 +271,11 @@ void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact ...@@ -258,6 +271,11 @@ void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact
} }
} }
void PX4FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
return PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion);
}
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{ {
QList<MAV_CMD> list; QList<MAV_CMD> list;
...@@ -571,5 +589,3 @@ QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_in ...@@ -571,5 +589,3 @@ QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_in
{ {
return new QGCCameraControl(info, vehicle, compID, parent); return new QGCCameraControl(info, vehicle, compID, parent);
} }
...@@ -56,10 +56,11 @@ public: ...@@ -56,10 +56,11 @@ public:
void initializeVehicle (Vehicle* vehicle) override; void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override; bool sendHomePositionToVehicle (void) override;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override;
FactMetaData* getMetaDataForFact (QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) override;
QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString missionCommandOverrides (MAV_TYPE vehicleType) const override;
QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); } QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); }
QString internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } QString internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override;
QObject* loadParameterMetaData (const QString& metaDataFile) final; QObject* loadParameterMetaData (const QString& metaDataFile) final;
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); } QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
......
...@@ -186,6 +186,20 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData ...@@ -186,6 +186,20 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
category = QStringLiteral("Standard"); category = QStringLiteral("Standard");
} }
bool volatileValue = false;
bool readOnly = false;
QString volatileStr = xml.attributes().value("volatile").toString();
if (volatileStr.compare(QStringLiteral("true")) == 0) {
volatileValue = true;
readOnly = true;
}
if (!volatileValue) {
QString readOnlyStr = xml.attributes().value("readonly").toString();
if (readOnlyStr.compare(QStringLiteral("true")) == 0) {
readOnly = true;
}
}
qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault;
// Convert type from string to FactMetaData::ValueType_t // Convert type from string to FactMetaData::ValueType_t
...@@ -211,6 +225,8 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData ...@@ -211,6 +225,8 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
metaData->setName(name); metaData->setName(name);
metaData->setCategory(category); metaData->setCategory(category);
metaData->setGroup(factGroup); metaData->setGroup(factGroup);
metaData->setReadOnly(readOnly);
metaData->setVolatileValue(volatileValue);
if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) {
QVariant varDefault; QVariant varDefault;
...@@ -387,6 +403,17 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData ...@@ -387,6 +403,17 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
} }
} }
FactMetaData* PX4ParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType)
{
Q_UNUSED(vehicleType)
if (_mapParameterName2FactMetaData.contains(name)) {
return _mapParameterName2FactMetaData[name];
} else {
return NULL;
}
}
void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{ {
Q_UNUSED(vehicleType) Q_UNUSED(vehicleType)
......
...@@ -33,8 +33,9 @@ class PX4ParameterMetaData : public QObject ...@@ -33,8 +33,9 @@ class PX4ParameterMetaData : public QObject
public: public:
PX4ParameterMetaData(void); PX4ParameterMetaData(void);
void loadParameterFactMetaDataFile (const QString& metaDataFile); void loadParameterFactMetaDataFile (const QString& metaDataFile);
void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType); FactMetaData* getMetaDataForFact (const QString& name, MAV_TYPE vehicleType);
void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType);
static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);
......
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