diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 8d882983789fec0def448f3f36cdc142ce906bcd..7363a09d6d614f34c400071482f2922fe103da78 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -497,6 +497,16 @@ int Fact::decimalPlaces(void) const } } +QString Fact::category(void) const +{ + if (_metaData) { + return _metaData->category(); + } else { + qWarning() << kMissingMetadata << name(); + return QString(); + } +} + QString Fact::group(void) const { if (_metaData) { diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index c8888ea5d42cca87edf7d0061aeb54850a9bd92c..34ba32ced5f81344d2373c3f90b16cc45023789a 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -48,6 +48,7 @@ public: Q_PROPERTY(QStringList enumStrings READ enumStrings NOTIFY enumsChanged) Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged) Q_PROPERTY(QVariantList enumValues READ enumValues NOTIFY enumsChanged) + Q_PROPERTY(QString category READ category CONSTANT) Q_PROPERTY(QString group READ group CONSTANT) Q_PROPERTY(QString longDescription READ longDescription CONSTANT) Q_PROPERTY(QVariant max READ cookedMax CONSTANT) @@ -91,6 +92,7 @@ public: QStringList enumStrings (void) const; QString enumStringValue (void); // This is not const, since an unknown value can modify the enum lists QVariantList enumValues (void) const; + QString category (void) const; QString group (void) const; QString longDescription (void) const; QVariant rawMax (void) const; diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index ede52cf949ea693527dc4e47ad02abfc7d044182..705b32a38d3102574f14c3ce074a9f711a1e559f 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -32,6 +32,9 @@ const qreal FactMetaData::UnitConsts_s::milesToMeters = 1609.344; const qreal FactMetaData::UnitConsts_s::feetToMeters = 0.3048; const qreal FactMetaData::UnitConsts_s::inchesToCentimeters = 2.54; +const QString FactMetaData::defaultCategory = tr("Other"); +const QString FactMetaData::defaultGroup = tr("Misc"); + // Built in translations for all Facts const FactMetaData::BuiltInTranslation_s FactMetaData::_rgBuiltInTranslations[] = { { "centi-degrees", "deg", FactMetaData::_centiDegreesToDegrees, FactMetaData::_degreesToCentiDegrees }, @@ -76,43 +79,45 @@ const char* FactMetaData::_maxJsonKey = "max"; const char* FactMetaData::_hasControlJsonKey = "control"; FactMetaData::FactMetaData(QObject* parent) - : QObject(parent) - , _type(valueTypeInt32) - , _decimalPlaces(unknownDecimalPlaces) - , _rawDefaultValue(0) + : QObject (parent) + , _type (valueTypeInt32) + , _decimalPlaces (unknownDecimalPlaces) + , _rawDefaultValue (0) , _defaultValueAvailable(false) - , _group("*Default Group") - , _rawMax(_maxForType()) - , _maxIsDefaultForType(true) - , _rawMin(_minForType()) - , _minIsDefaultForType(true) - , _rawTranslator(_defaultTranslator) - , _cookedTranslator(_defaultTranslator) - , _rebootRequired(false) - , _increment(std::numeric_limits::quiet_NaN()) - , _hasControl(true) - , _readOnly(false) + , _category (defaultCategory) + , _group (defaultGroup) + , _rawMax (_maxForType()) + , _maxIsDefaultForType (true) + , _rawMin (_minForType()) + , _minIsDefaultForType (true) + , _rawTranslator (_defaultTranslator) + , _cookedTranslator (_defaultTranslator) + , _rebootRequired (false) + , _increment (std::numeric_limits::quiet_NaN()) + , _hasControl (true) + , _readOnly (false) { } FactMetaData::FactMetaData(ValueType_t type, QObject* parent) - : QObject(parent) - , _type(type) - , _decimalPlaces(unknownDecimalPlaces) - , _rawDefaultValue(0) + : QObject (parent) + , _type (type) + , _decimalPlaces (unknownDecimalPlaces) + , _rawDefaultValue (0) , _defaultValueAvailable(false) - , _group("*Default Group") - , _rawMax(_maxForType()) - , _maxIsDefaultForType(true) - , _rawMin(_minForType()) - , _minIsDefaultForType(true) - , _rawTranslator(_defaultTranslator) - , _cookedTranslator(_defaultTranslator) - , _rebootRequired(false) - , _increment(std::numeric_limits::quiet_NaN()) - , _hasControl(true) - , _readOnly(false) + , _category (defaultCategory) + , _group (defaultGroup) + , _rawMax (_maxForType()) + , _maxIsDefaultForType (true) + , _rawMin (_minForType()) + , _minIsDefaultForType (true) + , _rawTranslator (_defaultTranslator) + , _cookedTranslator (_defaultTranslator) + , _rebootRequired (false) + , _increment (std::numeric_limits::quiet_NaN()) + , _hasControl (true) + , _readOnly (false) { } @@ -124,23 +129,24 @@ FactMetaData::FactMetaData(const FactMetaData& other, QObject* parent) } FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent) - : QObject(parent) - , _type(type) - , _decimalPlaces(unknownDecimalPlaces) - , _rawDefaultValue(0) + : QObject (parent) + , _type (type) + , _decimalPlaces (unknownDecimalPlaces) + , _rawDefaultValue (0) , _defaultValueAvailable(false) - , _group("*Default Group") - , _rawMax(_maxForType()) - , _maxIsDefaultForType(true) - , _rawMin(_minForType()) - , _minIsDefaultForType(true) - , _name(name) - , _rawTranslator(_defaultTranslator) - , _cookedTranslator(_defaultTranslator) - , _rebootRequired(false) - , _increment(std::numeric_limits::quiet_NaN()) - , _hasControl(true) - , _readOnly(false) + , _category (defaultCategory) + , _group (defaultGroup) + , _rawMax (_maxForType()) + , _maxIsDefaultForType (true) + , _rawMin (_minForType()) + , _minIsDefaultForType (true) + , _name (name) + , _rawTranslator (_defaultTranslator) + , _cookedTranslator (_defaultTranslator) + , _rebootRequired (false) + , _increment (std::numeric_limits::quiet_NaN()) + , _hasControl (true) + , _readOnly (false) { } @@ -154,6 +160,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) _bitmaskValues = other._bitmaskValues; _enumStrings = other._enumStrings; _enumValues = other._enumValues; + _category = other._category; _group = other._group; _longDescription = other._longDescription; _rawMax = other._rawMax; diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 2dd480f77adc959c58cec94bb398a285686ef4eb..a357c726b684d625f4875234e7ea62c54258d18e 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -84,6 +84,7 @@ public: QVariantList bitmaskValues (void) const { return _bitmaskValues; } QStringList enumStrings (void) const { return _enumStrings; } QVariantList enumValues (void) const { return _enumValues; } + QString category (void) const { return _category; } QString group (void) const { return _group; } QString longDescription (void) const { return _longDescription;} QVariant rawMax (void) const { return _rawMax; } @@ -118,6 +119,7 @@ public: void setRawDefaultValue (const QVariant& rawDefaultValue); void setBitmaskInfo (const QStringList& strings, const QVariantList& values); void setEnumInfo (const QStringList& strings, const QVariantList& values); + void setCategory (const QString& category) { _category = category; } void setGroup (const QString& group) { _group = group; } void setLongDescription (const QString& longDescription) { _longDescription = longDescription;} void setRawMax (const QVariant& rawMax); @@ -158,6 +160,9 @@ public: static ValueType_t stringToType(const QString& typeString, bool& unknownType); static size_t typeToSize(ValueType_t type); + static const QString defaultCategory; + static const QString defaultGroup; + private: QVariant _minForType(void) const; QVariant _maxForType(void) const; @@ -217,6 +222,7 @@ private: QVariantList _bitmaskValues; QStringList _enumStrings; QVariantList _enumValues; + QString _category; QString _group; QString _longDescription; QVariant _rawMax; diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 9e8d105b5e36b14bd2aea3b15b3fd70e40235c1a..8858711ef0425ba58db726de2687b18b08b05ad8 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -178,8 +178,8 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString } if (!_waitingReadParamIndexMap[componentId].contains(parameterId) && - !_waitingReadParamNameMap[componentId].contains(parameterName) && - !_waitingWriteParamNameMap[componentId].contains(parameterName)) { + !_waitingReadParamNameMap[componentId].contains(parameterName) && + !_waitingWriteParamNameMap[componentId].contains(parameterName)) { qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName; } @@ -265,34 +265,34 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString FactMetaData::ValueType_t factType; switch (mavType) { - case MAV_PARAM_TYPE_UINT8: - factType = FactMetaData::valueTypeUint8; - break; - case MAV_PARAM_TYPE_INT8: - factType = FactMetaData::valueTypeInt8; - break; - case MAV_PARAM_TYPE_UINT16: - factType = FactMetaData::valueTypeUint16; - break; - case MAV_PARAM_TYPE_INT16: - factType = FactMetaData::valueTypeInt16; - break; - case MAV_PARAM_TYPE_UINT32: - factType = FactMetaData::valueTypeUint32; - break; - case MAV_PARAM_TYPE_INT32: - factType = FactMetaData::valueTypeInt32; - break; - case MAV_PARAM_TYPE_REAL32: - factType = FactMetaData::valueTypeFloat; - break; - case MAV_PARAM_TYPE_REAL64: - factType = FactMetaData::valueTypeDouble; - break; - default: - factType = FactMetaData::valueTypeInt32; - qCritical() << "Unsupported fact type" << mavType; - break; + case MAV_PARAM_TYPE_UINT8: + factType = FactMetaData::valueTypeUint8; + break; + case MAV_PARAM_TYPE_INT8: + factType = FactMetaData::valueTypeInt8; + break; + case MAV_PARAM_TYPE_UINT16: + factType = FactMetaData::valueTypeUint16; + break; + case MAV_PARAM_TYPE_INT16: + factType = FactMetaData::valueTypeInt16; + break; + case MAV_PARAM_TYPE_UINT32: + factType = FactMetaData::valueTypeUint32; + break; + case MAV_PARAM_TYPE_INT32: + factType = FactMetaData::valueTypeInt32; + break; + case MAV_PARAM_TYPE_REAL32: + factType = FactMetaData::valueTypeFloat; + break; + case MAV_PARAM_TYPE_REAL64: + factType = FactMetaData::valueTypeDouble; + break; + default: + factType = FactMetaData::valueTypeInt32; + qCritical() << "Unsupported fact type" << mavType; + break; } Fact* fact = new Fact(componentId, parameterName, factType, this); @@ -325,7 +325,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString // When we are getting the very last component param index, reset the group maps to update for the // new params. By handling this here, we can pick up components which finish up later than the default // component param set. - _setupGroupMap(); + _setupCategoryMap(); } if (_prevWaitingWriteParamNameCount != 0 && waitingWriteParamNameCount == 0) { @@ -511,22 +511,20 @@ QStringList ParameterManager::parameterNames(int componentId) return names; } -void ParameterManager::_setupGroupMap(void) +void ParameterManager::_setupCategoryMap(void) { // Must be able to handle being called multiple times - _mapGroup2ParameterName.clear(); + _categoryMap.clear(); - foreach (int componentId, _mapParameterName2Variant.keys()) { - foreach (const QString &name, _mapParameterName2Variant[componentId].keys()) { - Fact* fact = _mapParameterName2Variant[componentId][name].value(); - _mapGroup2ParameterName[componentId][fact->group()] += name; - } + foreach (const QString &name, _mapParameterName2Variant[_vehicle->defaultComponentId()].keys()) { + Fact* fact = _mapParameterName2Variant[_vehicle->defaultComponentId()][name].value(); + _categoryMap[fact->category()][fact->group()] += name; } } -const QMap >& ParameterManager::getGroupMap(void) +const QMap >& ParameterManager::getCategoryMap(void) { - return _mapGroup2ParameterName; + return _categoryMap; } /// Requests missing index based parameters from the vehicle. @@ -687,37 +685,37 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN p.param_type = _factTypeToMavType(factType); switch (factType) { - case FactMetaData::valueTypeUint8: - union_value.param_uint8 = (uint8_t)value.toUInt(); - break; + case FactMetaData::valueTypeUint8: + union_value.param_uint8 = (uint8_t)value.toUInt(); + break; - case FactMetaData::valueTypeInt8: - union_value.param_int8 = (int8_t)value.toInt(); - break; + case FactMetaData::valueTypeInt8: + union_value.param_int8 = (int8_t)value.toInt(); + break; - case FactMetaData::valueTypeUint16: - union_value.param_uint16 = (uint16_t)value.toUInt(); - break; + case FactMetaData::valueTypeUint16: + union_value.param_uint16 = (uint16_t)value.toUInt(); + break; - case FactMetaData::valueTypeInt16: - union_value.param_int16 = (int16_t)value.toInt(); - break; + case FactMetaData::valueTypeInt16: + union_value.param_int16 = (int16_t)value.toInt(); + break; - case FactMetaData::valueTypeUint32: - union_value.param_uint32 = (uint32_t)value.toUInt(); - break; + case FactMetaData::valueTypeUint32: + union_value.param_uint32 = (uint32_t)value.toUInt(); + break; - case FactMetaData::valueTypeFloat: - union_value.param_float = value.toFloat(); - break; + case FactMetaData::valueTypeFloat: + union_value.param_float = value.toFloat(); + break; - default: - qCritical() << "Unsupported fact type" << factType; - // fall through + default: + qCritical() << "Unsupported fact type" << factType; + // fall through - case FactMetaData::valueTypeInt32: - union_value.param_int32 = (int32_t)value.toInt(); - break; + case FactMetaData::valueTypeInt32: + union_value.param_int32 = (int32_t)value.toInt(); + break; } p.param_value = union_value.param_float; @@ -938,77 +936,77 @@ void ParameterManager::writeParametersToStream(QTextStream &stream) MAV_PARAM_TYPE ParameterManager::_factTypeToMavType(FactMetaData::ValueType_t factType) { switch (factType) { - case FactMetaData::valueTypeUint8: - return MAV_PARAM_TYPE_UINT8; + case FactMetaData::valueTypeUint8: + return MAV_PARAM_TYPE_UINT8; - case FactMetaData::valueTypeInt8: - return MAV_PARAM_TYPE_INT8; + case FactMetaData::valueTypeInt8: + return MAV_PARAM_TYPE_INT8; - case FactMetaData::valueTypeUint16: - return MAV_PARAM_TYPE_UINT16; + case FactMetaData::valueTypeUint16: + return MAV_PARAM_TYPE_UINT16; - case FactMetaData::valueTypeInt16: - return MAV_PARAM_TYPE_INT16; + case FactMetaData::valueTypeInt16: + return MAV_PARAM_TYPE_INT16; - case FactMetaData::valueTypeUint32: - return MAV_PARAM_TYPE_UINT32; + case FactMetaData::valueTypeUint32: + return MAV_PARAM_TYPE_UINT32; - case FactMetaData::valueTypeFloat: - return MAV_PARAM_TYPE_REAL32; + case FactMetaData::valueTypeFloat: + return MAV_PARAM_TYPE_REAL32; - default: - qWarning() << "Unsupported fact type" << factType; - // fall through + default: + qWarning() << "Unsupported fact type" << factType; + // fall through - case FactMetaData::valueTypeInt32: - return MAV_PARAM_TYPE_INT32; + case FactMetaData::valueTypeInt32: + return MAV_PARAM_TYPE_INT32; } } FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE mavType) { switch (mavType) { - case MAV_PARAM_TYPE_UINT8: - return FactMetaData::valueTypeUint8; + case MAV_PARAM_TYPE_UINT8: + return FactMetaData::valueTypeUint8; - case MAV_PARAM_TYPE_INT8: - return FactMetaData::valueTypeInt8; + case MAV_PARAM_TYPE_INT8: + return FactMetaData::valueTypeInt8; - case MAV_PARAM_TYPE_UINT16: - return FactMetaData::valueTypeUint16; + case MAV_PARAM_TYPE_UINT16: + return FactMetaData::valueTypeUint16; - case MAV_PARAM_TYPE_INT16: - return FactMetaData::valueTypeInt16; + case MAV_PARAM_TYPE_INT16: + return FactMetaData::valueTypeInt16; - case MAV_PARAM_TYPE_UINT32: - return FactMetaData::valueTypeUint32; + case MAV_PARAM_TYPE_UINT32: + return FactMetaData::valueTypeUint32; - case MAV_PARAM_TYPE_REAL32: - return FactMetaData::valueTypeFloat; + case MAV_PARAM_TYPE_REAL32: + return FactMetaData::valueTypeFloat; - default: - qWarning() << "Unsupported mav param type" << mavType; - // fall through + default: + qWarning() << "Unsupported mav param type" << mavType; + // fall through - case MAV_PARAM_TYPE_INT32: - return FactMetaData::valueTypeInt32; + case MAV_PARAM_TYPE_INT32: + return FactMetaData::valueTypeInt32; } } void ParameterManager::_addMetaDataToDefaultComponent(void) { - if (_parameterMetaData) { - return; - } + if (_parameterMetaData) { + return; + } - QString metaDataFile; - int majorVersion, minorVersion; + QString metaDataFile; + int majorVersion, minorVersion; - // Load best parameter meta data set - metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); - qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion; + // Load best parameter meta data set + metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); + qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion; - _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); + _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); // Loop over all parameters in default component adding meta data QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()]; @@ -1349,7 +1347,7 @@ void ParameterManager::_loadOfflineEditingParams(void) } _addMetaDataToDefaultComponent(); - _setupGroupMap(); + _setupCategoryMap(); _parametersReady = true; _initialLoadComplete = true; } diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index 7714075d7ac6605b0e73f6ae0a56f7dc45c2213c..a800acc5d580b81b2a96757b9a60121d2c64332b 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -84,7 +84,7 @@ public: /// @param name Parameter name Fact* getParameter(int componentId, const QString& name); - const QMap >& getGroupMap(void); + const QMap >& getCategoryMap(void); /// Returns error messages from loading QString readParametersFromStream(QTextStream& stream); @@ -137,7 +137,7 @@ protected: private: static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); int _actualComponentId(int componentId); - void _setupGroupMap(void); + void _setupCategoryMap(void); void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeLocalParamCache(int vehicleId, int componentId); @@ -159,10 +159,9 @@ private: QMap _mapParameterName2Variant; QMap > _mapParameterId2Name; - - /// First mapping is by component id - /// Second mapping is group name, to Fact - QMap > _mapGroup2ParameterName; + + // Category map of default component parameters + QMap > _categoryMap; double _loadProgress; ///< Parameter load progess, [0.0,1.0] bool _parametersReady; ///< true: parameter load complete diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index f5154f921b16e52488b436624990fedb46e38195..7cb78cb48f916f7d95619f7515c7362dc90cf086 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -233,14 +233,18 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData QString group = name.split('_').first(); group = group.remove(QRegExp("[0-9]*$")); // remove any numbers from the end + QString category = xml.attributes().value("user").toString(); + if (category.isEmpty()) { + category = QStringLiteral("Advanced"); + } + QString shortDescription = xml.attributes().value("humanName").toString(); QString longDescription = xml.attributes().value("documentation").toString(); - QString userLevel = xml.attributes().value("user").toString(); qCDebug(APMParameterMetaDataVerboseLog) << "Found parameter name:" << name << "short Desc:" << shortDescription << "longDescription:" << longDescription - << "user level: " << userLevel + << "category: " << category << "group: " << group; Q_ASSERT(!rawMetaData); @@ -254,6 +258,7 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData } qCDebug(APMParameterMetaDataVerboseLog) << "inserting metadata for field" << name; rawMetaData->name = name; + rawMetaData->category = category; rawMetaData->group = group; rawMetaData->shortDescription = shortDescription; rawMetaData->longDescription = longDescription; @@ -301,7 +306,7 @@ void APMParameterMetaData::correctGroupMemberships(ParameterNametoFactMetaDataMa foreach(const QString& groupName, groupMembers.keys()) { if (groupMembers[groupName].count() == 1) { foreach(const QString& parameter, groupMembers.value(groupName)) { - parameterToFactMetaDataMap[parameter]->group = "others"; + parameterToFactMetaDataMap[parameter]->group = FactMetaData::defaultGroup; } } } @@ -434,6 +439,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) } metaData->setName(rawMetaData->name); + metaData->setCategory(rawMetaData->category); metaData->setGroup(rawMetaData->group); metaData->setRebootRequired(rawMetaData->rebootRequired); diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.h b/src/FirmwarePlugin/APM/APMParameterMetaData.h index dc4c4600d6daecfbd65c89a154145487005f4bfb..675476ed2770f743da7187da9c097380a4cf9f76 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.h +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.h @@ -32,6 +32,7 @@ public: { } QString name; + QString category; QString group; QString shortDescription; QString longDescription; diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index 9b1389273a3a43855e36264097ab825966272324..61719557c9e82db431e703b69e99178c4c2186d4 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -181,6 +181,11 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData QString type = xml.attributes().value("type").toString(); QString strDefault = xml.attributes().value("default").toString(); + QString category = xml.attributes().value("category").toString(); + if (category.isEmpty()) { + category = QStringLiteral("Standard"); + } + qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; // Convert type from string to FactMetaData::ValueType_t @@ -196,7 +201,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData metaData = new FactMetaData(foundType); Q_CHECK_PTR(metaData); if (_mapParameterName2FactMetaData.contains(name)) { - // We can't trust the meta dafa since we have dups + // We can't trust the meta data since we have dups qCWarning(PX4ParameterMetaDataLog) << "Duplicate parameter found:" << name; badMetaData = true; // Reset to default meta data @@ -204,6 +209,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData } else { _mapParameterName2FactMetaData[name] = metaData; metaData->setName(name); + metaData->setCategory(category); metaData->setGroup(factGroup); if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { diff --git a/src/PlanView/SectionHeader.qml b/src/PlanView/SectionHeader.qml index bcc63abe3c97a2d53707e0b33bf6119a1979d2c8..9f0b6b8a7a582e3f0d9ef43dd17607f7b6559f2d 100644 --- a/src/PlanView/SectionHeader.qml +++ b/src/PlanView/SectionHeader.qml @@ -46,8 +46,9 @@ FocusScope { } QGCLabel { - id: label - Layout.fillWidth: true + id: label + anchors.left: parent.left + anchors.right: parent.right QGCColoredImage { id: image diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index 2159e6435cd0732962d90baa658cf9de1bb08ab3..2d9c667c912dd558502eafdbf108c2a06caa831d 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -7,13 +7,10 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - -import QtQuick 2.3 -import QtQuick.Controls 1.2 -import QtQuick.Dialogs 1.2 +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtQuick.Dialogs 1.2 +import QtQuick.Layouts 1.2 import QGroundControl 1.0 import QGroundControl.Controls 1.0 @@ -44,6 +41,8 @@ QGCView { } } + ExclusiveGroup { id: sectionGroup } + QGCViewPanel { id: panel anchors.fill: parent @@ -158,48 +157,58 @@ QGCView { anchors.bottom: parent.bottom clip: true pixelAligned: true - contentHeight: groupedViewComponentColumn.height - contentWidth: groupedViewComponentColumn.width + contentHeight: groupedViewCategoryColumn.height flickableDirection: Flickable.VerticalFlick visible: !_searchFilter - Column { - id: groupedViewComponentColumn - spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25) + ColumnLayout { + id: groupedViewCategoryColumn + anchors.left: parent.left + anchors.right: parent.right + spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25) Repeater { - model: controller.componentIds + model: controller.categories Column { - id: componentColumn - spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25) + Layout.fillWidth: true + spacing: Math.ceil(ScreenTools.defaultFontPixelHeight * 0.25) - readonly property int componentId: modelData + readonly property string category: modelData - QGCLabel { - text: qsTr("Component #: %1").arg(componentId.toString()) - font.family: ScreenTools.demiboldFontFamily - anchors.horizontalCenter: parent.horizontalCenter + SectionHeader { + id: categoryHeader + text: category + checked: controller.currentCategory == text + exclusiveGroup: sectionGroup + + onCheckedChanged: { + if (checked) { + controller.currentCategory = category + controller.currentGroup = controller.getGroupsForCategory(category)[0] + } + } } - ExclusiveGroup { id: groupGroup } + ExclusiveGroup { id: buttonGroup } Repeater { - model: controller.getGroupsForComponent(componentId) + model: categoryHeader.checked ? controller.getGroupsForCategory(category) : 0 QGCButton { width: ScreenTools.defaultFontPixelWidth * 25 text: groupName height: _rowHeight - exclusiveGroup: setupButtonGroup + checked: controller.currentGroup == text + exclusiveGroup: buttonGroup readonly property string groupName: modelData onClicked: { checked = true - _rowWidth = 10 - controller.currentComponentId = componentId - controller.currentGroup = groupName + _rowWidth = 10 + controller.currentCategory = category + controller.currentGroup = groupName } } } diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index b665750af9548ee4897a941e5eac929728246438..2f980a227f11353752ad9b97b9afff3deb6cbd85 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -27,22 +27,23 @@ /// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens. ParameterEditorController::ParameterEditorController(void) - : _currentComponentId(_vehicle->defaultComponentId()) + : _currentCategory("Standard") // FIXME: firmware specific , _parameters(new QmlObjectListModel(this)) { - const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); - foreach (int componentId, groupMap.keys()) { - _componentIds += QString("%1").arg(componentId); - } + const QMap >& categoryMap = _vehicle->parameterManager()->getCategoryMap(); + _categories = categoryMap.keys(); + + // Move default category to front + _categories.removeOne(_currentCategory); + _categories.prepend(_currentCategory); // Be careful about no parameters - if (groupMap.contains(_currentComponentId) && groupMap[_currentComponentId].size() != 0) { - _currentGroup = groupMap[_currentComponentId].keys()[0]; + if (categoryMap.contains(_currentCategory) && categoryMap[_currentCategory].size() != 0) { + _currentGroup = categoryMap[_currentCategory].keys()[0]; } _updateParameters(); connect(this, &ParameterEditorController::searchTextChanged, this, &ParameterEditorController::_updateParameters); - connect(this, &ParameterEditorController::currentComponentIdChanged, this, &ParameterEditorController::_updateParameters); connect(this, &ParameterEditorController::currentGroupChanged, this, &ParameterEditorController::_updateParameters); } @@ -51,29 +52,29 @@ ParameterEditorController::~ParameterEditorController() } -QStringList ParameterEditorController::getGroupsForComponent(int componentId) +QStringList ParameterEditorController::getGroupsForCategory(const QString& category) { - const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); + const QMap >& categoryMap = _vehicle->parameterManager()->getCategoryMap(); - return groupMap[componentId].keys(); + return categoryMap[category].keys(); } -QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group) +QStringList ParameterEditorController::getParametersForGroup(const QString& category, const QString& group) { - const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); + const QMap >& categoryMap = _vehicle->parameterManager()->getCategoryMap(); - return groupMap[componentId][group]; + return categoryMap[category][group]; } -QStringList ParameterEditorController::searchParametersForComponent(int componentId, const QString& searchText, bool searchInName, bool searchInDescriptions) +QStringList ParameterEditorController::searchParameters(const QString& searchText, bool searchInName, bool searchInDescriptions) { QStringList list; - foreach(const QString ¶mName, _vehicle->parameterManager()->parameterNames(componentId)) { + foreach(const QString ¶mName, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { if (searchText.isEmpty()) { list += paramName; } else { - Fact* fact = _vehicle->parameterManager()->getParameter(componentId, paramName); + Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), paramName); if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { list += paramName; @@ -161,9 +162,9 @@ void ParameterEditorController::_updateParameters(void) QStringList searchItems = _searchText.split(' ', QString::SkipEmptyParts); if (searchItems.isEmpty()) { - const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); - foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { - newParameterList.append(_vehicle->parameterManager()->getParameter(_currentComponentId, parameter)); + const QMap >& categoryMap = _vehicle->parameterManager()->getCategoryMap(); + foreach (const QString& parameter, categoryMap[_currentCategory][_currentGroup]) { + newParameterList.append(_vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter)); } } else { foreach(const QString ¶meter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { diff --git a/src/QmlControls/ParameterEditorController.h b/src/QmlControls/ParameterEditorController.h index c37e0d89e04f372d43379e4e3290123dba78c976..8b0f442fb2f6a28938eb720d3e13fe265ceb3d3d 100644 --- a/src/QmlControls/ParameterEditorController.h +++ b/src/QmlControls/ParameterEditorController.h @@ -31,14 +31,14 @@ public: ~ParameterEditorController(); Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged) - Q_PROPERTY(int currentComponentId MEMBER _currentComponentId NOTIFY currentComponentIdChanged) + Q_PROPERTY(QString currentCategory MEMBER _currentCategory NOTIFY currentCategoryChanged) Q_PROPERTY(QString currentGroup MEMBER _currentGroup NOTIFY currentGroupChanged) Q_PROPERTY(QmlObjectListModel* parameters MEMBER _parameters CONSTANT) - Q_PROPERTY(QVariantList componentIds MEMBER _componentIds CONSTANT) + Q_PROPERTY(QStringList categories MEMBER _categories CONSTANT) - Q_INVOKABLE QStringList getGroupsForComponent(int componentId); - Q_INVOKABLE QStringList getParametersForGroup(int componentId, QString group); - Q_INVOKABLE QStringList searchParametersForComponent(int componentId, const QString& searchText, bool searchInName=true, bool searchInDescriptions=true); + Q_INVOKABLE QStringList getGroupsForCategory(const QString& category); + Q_INVOKABLE QStringList getParametersForGroup(const QString& category, const QString& group); + Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true); Q_INVOKABLE void clearRCToParam(void); Q_INVOKABLE void saveToFile(const QString& filename); @@ -51,7 +51,7 @@ public: signals: void searchTextChanged(QString searchText); - void currentComponentIdChanged(int componentId); + void currentCategoryChanged(QString category); void currentGroupChanged(QString group); void showErrorMessage(const QString& errorMsg); @@ -59,9 +59,9 @@ private slots: void _updateParameters(void); private: - QVariantList _componentIds; + QStringList _categories; QString _searchText; - int _currentComponentId; + QString _currentCategory; QString _currentGroup; QmlObjectListModel* _parameters; };