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

Merge pull request #9044 from DonLakeFlyer/RegexParamMetadata

COMPONENT_INFORMATION:COMP_METADATA_TYPE_PARAMETER Changed parameter name regex support
parents a11fb32c 14ab96cd
......@@ -76,30 +76,58 @@ void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString&
}
FactMetaData* newMetaData = FactMetaData::createFromJsonObject(parameterValue.toObject(), emptyDefineMap, this);
_nameToMetaDataMap[newMetaData->name()] = newMetaData;
QRegularExpression regexNameIncludesRegex("/\\(.+\\)/");
QRegularExpressionMatch match = regexNameIncludesRegex.match(newMetaData->name());
if (match.hasMatch()) {
QString regexParamName = newMetaData->name();
regexParamName.replace(QRegularExpression("/(\\(.+\\))/"), "\\1");
newMetaData->setName(regexParamName);
_regexNameMetaDataList.append(RegexFactMetaDataPair_t(newMetaData->name(), newMetaData));
} else {
_nameToMetaDataMap[newMetaData->name()] = newMetaData;
}
}
}
FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaData::ValueType_t type)
{
FactMetaData* factMetaData = nullptr;
if (_opaqueParameterMetaData) {
return vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType());
factMetaData = vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType());
} else {
QString indexTagName = name;
if (!_nameToMetaDataMap.contains(name)) {
// Checked for indexed parameter names: "FOO<#>_BAR" will match "FOO1_BAR"
QRegularExpression regex("\\d+");
indexTagName = indexTagName.replace(regex, _parameterIndexTag);
if (!_nameToMetaDataMap.contains(indexTagName)) {
indexTagName.clear();
if (_nameToMetaDataMap.contains(name)) {
factMetaData = _nameToMetaDataMap[name];
} else {
for (int i=0; i<_regexNameMetaDataList.count(); i++) {
const RegexFactMetaDataPair_t& pair = _regexNameMetaDataList[i];
QString regexParamName = pair.first;
QRegularExpression regex(regexParamName);
QRegularExpressionMatch match = regex.match(name);
QStringList captured = match.capturedTexts();
if (captured.count() == 2) {
factMetaData = new FactMetaData(*pair.second, this);
factMetaData->setName(name);
QString shortDescription = factMetaData->shortDescription();
shortDescription.replace("/1", captured[1]);
factMetaData->setShortDescription(shortDescription);
QString longDescription = factMetaData->shortDescription();
longDescription.replace("/1", captured[1]);
factMetaData->setLongDescription(longDescription);
}
}
if (!factMetaData) {
factMetaData = new FactMetaData(type, this);
}
_nameToMetaDataMap[name] = factMetaData;
}
if (indexTagName.isEmpty()) {
indexTagName = name;
_nameToMetaDataMap[name] = new FactMetaData(type, this);
}
return _nameToMetaDataMap[indexTagName];
}
return factMetaData;
}
bool CompInfoParam::_isParameterVolatile(const QString& name)
......
......@@ -44,8 +44,11 @@ private:
static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin (MAV_AUTOPILOT firmwareType);
static QString _parameterMetaDataFile (Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion);
typedef QPair<QString /* regexName */, FactMetaData*> RegexFactMetaDataPair_t;
bool _noJsonMetadata = true;
FactMetaData::NameToMetaDataMap_t _nameToMetaDataMap;
QList<RegexFactMetaDataPair_t> _regexNameMetaDataList;
QObject* _opaqueParameterMetaData = nullptr;
static const char* _cachedMetaDataFilePrefix;
......
......@@ -357,7 +357,7 @@
"maxValue": 1
},
{
"name": "BAT<#>_A_PER_V",
"name": "BAT/(\\d+)/_A_PER_V",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
......@@ -370,7 +370,7 @@
"maxValue": 3.40282e+38
},
{
"name": "BAT<#>_CAPACITY",
"name": "BAT/(\\d+)/_CAPACITY",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
......@@ -385,7 +385,7 @@
"maxValue": 100000
},
{
"name": "BAT<#>_I_CHANNEL",
"name": "BAT/(\\d+)/_I_CHANNEL",
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
......@@ -398,7 +398,7 @@
"maxValue": 2.14748e+09
},
{
"name": "BAT<#>_N_CELLS",
"name": "BAT/(\\d+)/_N_CELLS",
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
......@@ -473,12 +473,12 @@
"maxValue": 2.14748e+09
},
{
"name": "BAT<#>_R_INTERNAL",
"name": "BAT/(\\d+)/_R_INTERNAL",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "Explicitly defines the per cell internal resistance for battery 1",
"longDesc": "If non-negative, then this will be used in place of BAT<#>_V_LOAD_DROP for all calculations.",
"longDesc": "If non-negative, then this will be used in place of BAT/(\\d+)/_V_LOAD_DROP for all calculations.",
"units": "Ohm",
"default": -1,
"increment": 0.01,
......@@ -488,7 +488,7 @@
"maxValue": 0.2
},
{
"name": "BAT<#>_SOURCE",
"name": "BAT/(\\d+)/_SOURCE",
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
......@@ -515,7 +515,7 @@
"maxValue": 2.14748e+09
},
{
"name": "BAT<#>_V_CHANNEL",
"name": "BAT/(\\d+)/_V_CHANNEL",
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
......@@ -528,7 +528,7 @@
"maxValue": 2.14748e+09
},
{
"name": "BAT<#>_V_CHARGED",
"name": "BAT/(\\d+)/_V_CHARGED",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
......@@ -543,7 +543,7 @@
"maxValue": 3.40282e+38
},
{
"name": "BAT<#>_V_DIV",
"name": "BAT/(\\d+)/_V_DIV",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
......@@ -556,7 +556,7 @@
"maxValue": 3.40282e+38
},
{
"name": "BAT<#>_V_EMPTY",
"name": "BAT/(\\d+)/_V_EMPTY",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
......@@ -571,12 +571,12 @@
"maxValue": 3.40282e+38
},
{
"name": "BAT<#>_V_LOAD_DROP",
"name": "BAT/(\\d+)/_V_LOAD_DROP",
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "Voltage drop per cell on full throttle",
"longDesc": "This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT<#>_R_INTERNAL is set.",
"longDesc": "This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT/(\\d+)/_R_INTERNAL is set.",
"units": "V",
"default": 0.3,
"increment": 0.01,
......@@ -590,7 +590,7 @@
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_ADC_CHANNEL",
"shortDesc": "This parameter is deprecated. Please use BAT1_ADC_CHANNEL",
"default": -1,
"decimalPlaces": 3,
"minValue": -2.14748e+09,
......@@ -601,7 +601,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_A_PER_V",
"shortDesc": "This parameter is deprecated. Please use BAT1_A_PER_V",
"default": -1,
"decimalPlaces": 8,
"minValue": -3.40282e+38,
......@@ -612,7 +612,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_CAPACITY instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_CAPACITY instead",
"longDesc": "Defines the capacity of battery 1.",
"units": "mAh",
"default": -1,
......@@ -684,7 +684,7 @@
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_N_CELLS instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_N_CELLS instead",
"longDesc": "Defines the number of cells the attached battery consists of.",
"units": "S",
"default": 0,
......@@ -764,7 +764,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_R_INTERNAL instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_R_INTERNAL instead",
"longDesc": "If non-negative, then this will be used in place of BAT_V_LOAD_DROP for all calculations.",
"units": "Ohms",
"default": -1,
......@@ -778,7 +778,7 @@
"type": "Int32",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_SOURCE instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_SOURCE instead",
"longDesc": "Battery monitoring source. This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages.",
"default": 0,
"values": [
......@@ -800,7 +800,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_V_CHARGED instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_V_CHARGED instead",
"longDesc": "Defines the voltage where a single cell of battery 1 is considered full under a mild load. This will never be the nominal voltage of 4.2V",
"units": "V",
"default": 4.05,
......@@ -815,7 +815,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_V_DIV",
"shortDesc": "This parameter is deprecated. Please use BAT1_V_DIV",
"default": -1,
"decimalPlaces": 8,
"minValue": -3.40282e+38,
......@@ -826,7 +826,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_V_EMPTY instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_V_EMPTY instead",
"longDesc": "Defines the voltage where a single cell of battery 1 is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells.",
"units": "V",
"default": 3.5,
......@@ -841,7 +841,7 @@
"type": "Float",
"group": "Battery Calibration",
"category": "Standard",
"shortDesc": "This parameter is deprecated. Please use BAT<#>_V_LOAD_DROP instead",
"shortDesc": "This parameter is deprecated. Please use BAT1_V_LOAD_DROP instead",
"longDesc": "This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT_R_INTERNAL is set.",
"units": "V",
"default": 0.3,
......@@ -864,18 +864,18 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_EN",
"name": "CAL_ACC/(\\d+)/_EN",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
"shortDesc": "Accelerometer 0 enabled",
"shortDesc": "Accelerometer /1 enabled",
"default": 1,
"decimalPlaces": 3,
"minValue": -2.14748e+09,
"maxValue": 2.14748e+09
},
{
"name": "CAL_ACC<#>_ID",
"name": "CAL_ACC/(\\d+)/_ID",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -886,7 +886,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_ACC<#>_XOFF",
"name": "CAL_ACC/(\\d+)/_XOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -897,7 +897,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_XSCALE",
"name": "CAL_ACC/(\\d+)/_XSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -908,7 +908,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_YOFF",
"name": "CAL_ACC/(\\d+)/_YOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -919,7 +919,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_YSCALE",
"name": "CAL_ACC/(\\d+)/_YSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -930,7 +930,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_ZOFF",
"name": "CAL_ACC/(\\d+)/_ZOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -941,7 +941,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_ACC<#>_ZSCALE",
"name": "CAL_ACC/(\\d+)/_ZSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1014,7 +1014,7 @@
"maxValue": 2
},
{
"name": "CAL_GYRO<#>_EN",
"name": "CAL_GYRO/(\\d+)/_EN",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -1025,7 +1025,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_GYRO<#>_ID",
"name": "CAL_GYRO/(\\d+)/_ID",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -1036,7 +1036,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_GYRO<#>_XOFF",
"name": "CAL_GYRO/(\\d+)/_XOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1047,7 +1047,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_GYRO<#>_YOFF",
"name": "CAL_GYRO/(\\d+)/_YOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1058,7 +1058,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_GYRO<#>_ZOFF",
"name": "CAL_GYRO/(\\d+)/_ZOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1080,7 +1080,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_MAG<#>_EN",
"name": "CAL_MAG/(\\d+)/_EN",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -1091,7 +1091,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_MAG<#>_ID",
"name": "CAL_MAG/(\\d+)/_ID",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -1102,7 +1102,7 @@
"maxValue": 2.14748e+09
},
{
"name": "CAL_MAG<#>_ROT",
"name": "CAL_MAG/(\\d+)/_ROT",
"type": "Int32",
"group": "Sensor Calibration",
"category": "System",
......@@ -1225,7 +1225,7 @@
"maxValue": 30
},
{
"name": "CAL_MAG<#>_XCOMP",
"name": "CAL_MAG/(\\d+)/_XCOMP",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1236,7 +1236,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_XOFF",
"name": "CAL_MAG/(\\d+)/_XOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1247,7 +1247,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_XSCALE",
"name": "CAL_MAG/(\\d+)/_XSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1258,7 +1258,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_YCOMP",
"name": "CAL_MAG/(\\d+)/_YCOMP",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1269,7 +1269,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_YOFF",
"name": "CAL_MAG/(\\d+)/_YOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1280,7 +1280,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_YSCALE",
"name": "CAL_MAG/(\\d+)/_YSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1291,7 +1291,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_ZCOMP",
"name": "CAL_MAG/(\\d+)/_ZCOMP",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1302,7 +1302,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_ZOFF",
"name": "CAL_MAG/(\\d+)/_ZOFF",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -1313,7 +1313,7 @@
"maxValue": 3.40282e+38
},
{
"name": "CAL_MAG<#>_ZSCALE",
"name": "CAL_MAG/(\\d+)/_ZSCALE",
"type": "Float",
"group": "Sensor Calibration",
"category": "System",
......@@ -6320,7 +6320,7 @@
"maxValue": 3.40282e+38
},
{
"name": "GPS_<#>_CONFIG",
"name": "GPS_/(\\d+)/_CONFIG",
"type": "Int32",
"group": "GPS",
"category": "Standard",
......@@ -7578,7 +7578,7 @@
"maxValue": 3.40282e+38
},
{
"name": "MAV_<#>_CONFIG",
"name": "MAV_/(\\d+)/_CONFIG",
"type": "Int32",
"group": "MAVLink",
"category": "Standard",
......@@ -7633,7 +7633,7 @@
"maxValue": 2.14748e+09
},
{
"name": "MAV_<#>_FORWARD",
"name": "MAV_/(\\d+)/_FORWARD",
"type": "Int32",
"group": "MAVLink",
"category": "Standard",
......@@ -7646,7 +7646,7 @@
"maxValue": 2.14748e+09
},
{
"name": "MAV_<#>_MODE",
"name": "MAV_/(\\d+)/_MODE",
"type": "Int32",
"group": "MAVLink",
"category": "Standard",
......@@ -7693,7 +7693,7 @@
"maxValue": 2.14748e+09
},
{
"name": "MAV_<#>_RADIO_CTL",
"name": "MAV_/(\\d+)/_RADIO_CTL",
"type": "Int32",
"group": "MAVLink",
"category": "Standard",
......@@ -7706,7 +7706,7 @@
"maxValue": 2.14748e+09
},
{
"name": "MAV_<#>_RATE",
"name": "MAV_/(\\d+)/_RATE",
"type": "Int32",
"group": "MAVLink",
"category": "Standard",
......@@ -11828,7 +11828,7 @@
"maxValue": 1000
},
{
"name": "RC<#>_DZ",
"name": "RC/(\\d+)/_DZ",
"type": "Float",
"group": "Radio Calibration",
"category": "Standard",
......@@ -11840,7 +11840,7 @@
"maxValue": 100
},
{
"name": "RC<#>_MAX",
"name": "RC/(\\d+)/_MAX",
"type": "Float",
"group": "Radio Calibration",
"category": "Standard",
......@@ -11853,7 +11853,7 @@
"maxValue": 2200
},
{
"name": "RC<#>_MIN",
"name": "RC/(\\d+)/_MIN",
"type": "Float",
"group": "Radio Calibration",
"category": "Standard",
......@@ -11866,7 +11866,7 @@
"maxValue": 1500
},
{
"name": "RC<#>_REV",
"name": "RC/(\\d+)/_REV",
"type": "Float",
"group": "Radio Calibration",
"category": "Standard",
......@@ -11888,7 +11888,7 @@
"maxValue": 1
},
{
"name": "RC<#>_TRIM",
"name": "RC/(\\d+)/_TRIM",
"type": "Float",
"group": "Radio Calibration",
"category": "Standard",
......@@ -16149,7 +16149,7 @@
"maxValue": 2.14748e+09
},
{
"name": "SENS_MB12_<#>_ROT",
"name": "SENS_MB12_/(\\d+)/_ROT",
"type": "Int32",
"group": "Sensors",
"category": "Standard",
......@@ -16196,7 +16196,7 @@
"maxValue": 7
},
{
"name": "SENS_MPDT<#>_ROT",
"name": "SENS_MPDT/(\\d+)/_ROT",
"type": "Int32",
"group": "Sensors",
"category": "Standard",
......@@ -16419,7 +16419,7 @@
"maxValue": 2.14748e+09
},
{
"name": "SER_GPS<#>_BAUD",
"name": "SER_GPS/(\\d+)/_BAUD",
"type": "Int32",
"group": "Serial",
"category": "Standard",
......@@ -16657,7 +16657,7 @@
"maxValue": 2.14748e+09
},
{
"name": "SER_TEL<#>_BAUD",
"name": "SER_TEL/(\\d+)/_BAUD",
"type": "Int32",
"group": "Serial",
"category": "Standard",
......
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