QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FactMetaData.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QLoggingCategory>
4#include <QtCore/QJsonArray>
5#include <QtCore/QJsonObject>
6#include <QtCore/QObject>
7#include <QtCore/QString>
8#include <QtCore/QVariant>
9#include <QtQmlIntegration/QtQmlIntegration>
10
11Q_DECLARE_LOGGING_CATEGORY(FactMetaDataLog)
12
13class SettingsManager;
14
18class FactMetaData : public QObject
19{
20 Q_OBJECT
21 QML_ELEMENT
22
23 friend class SettingsManager;
24
25public:
42 Q_ENUM(ValueType_t)
43
44 typedef QVariant (*Translator)(const QVariant &from);
45
46 // Custom function to validate a cooked value.
47 // @return Error string for failed validation explanation to user. Empty string indicates no error.
48 typedef QString (*CustomCookedValidator)(const QVariant &cookedValue);
49
50 typedef QMap<QString /* param Name */, FactMetaData*> NameToMetaDataMap_t;
51
52 explicit FactMetaData(QObject *parent = nullptr);
53 explicit FactMetaData(ValueType_t type, QObject *parent = nullptr);
54 explicit FactMetaData(ValueType_t type, const QString &name, QObject *parent = nullptr);
55 explicit FactMetaData(const FactMetaData &other, QObject *parent = nullptr);
56 ~FactMetaData();
57
58 typedef QMap<QString, QString> DefineMap_t;
59
60 static QMap<QString, FactMetaData*> createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent);
61 static QMap<QString, FactMetaData*> createMapFromJsonArray(const QJsonArray &jsonArray, const DefineMap_t &defineMap, QObject *metaDataParent);
62
63 static FactMetaData *createFromJsonObject(const QJsonObject &json, const QMap<QString, QString> &defineMap, QObject *metaDataParent);
64
65 const FactMetaData &operator=(const FactMetaData &other);
66
68 static QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant &meters);
69
71 static QVariant appSettingsHorizontalDistanceUnitsToMeters(const QVariant &distance);
72
75
77 static QVariant metersToAppSettingsVerticalDistanceUnits(const QVariant &meters);
78
80 static QVariant appSettingsVerticalDistanceUnitsToMeters(const QVariant &distance);
81
84
86 static QVariant gramsToAppSettingsWeightUnits(const QVariant &grams);
87
89 static QVariant appSettingsWeightUnitsToGrams(const QVariant &weight);
90
92 static QString appSettingsWeightUnitsString();
93
95 static QVariant squareMetersToAppSettingsAreaUnits(const QVariant &squareMeters);
96
98 static QVariant appSettingsAreaUnitsToSquareMeters(const QVariant &area);
99
101 static QString appSettingsAreaUnitsString();
102
104 static QVariant metersSecondToAppSettingsSpeedUnits(const QVariant &metersSecond);
105
107 static QVariant appSettingsSpeedUnitsToMetersSecond(const QVariant &speed);
108
110 static QString appSettingsSpeedUnitsString();
111
112 static const QString defaultCategory() { return QString(kDefaultCategory); }
113 static const QString defaultGroup() { return QString(kDefaultGroup); }
114
115 // Splits a comma separated list of strings into a QStringList. Taking into account the possibility that
116 // the commas may have been translated to other characters such as chinese commas.
117 static QStringList splitTranslatedList(const QString &translatedList);
118
119 int decimalPlaces() const;
120 QVariant rawDefaultValue() const;
121 QVariant cookedDefaultValue() const { return _rawTranslator(rawDefaultValue()); }
122 bool defaultValueAvailable() const { return _defaultValueAvailable; }
123 QStringList bitmaskStrings() const { return _bitmaskStrings; }
124 QVariantList bitmaskValues() const { return _bitmaskValues; }
125 QStringList enumStrings() const { return _enumStrings; }
126 QVariantList enumValues() const { return _enumValues; }
127 QString category() const { return _category; }
128 QString group() const { return _group; }
129 QString longDescription() const { return _longDescription;}
130 QVariant rawMax() const { return _rawMax; }
131 QVariant cookedMax() const;
132 bool maxIsDefaultForType() const { return (_rawMax == _maxForType()); }
133 QVariant rawMin() const { return _rawMin; }
134 QVariant cookedMin() const;
135 bool minIsDefaultForType() const { return (_rawMin == _minForType()); }
136 QVariant rawUserMin() const { return _rawUserMin; }
137 QVariant rawUserMax() const { return _rawUserMax; }
138 QVariant cookedUserMin() const;
139 QVariant cookedUserMax() const;
140 QString name() const { return _name; }
141 QString shortDescription() const { return _shortDescription; }
142 ValueType_t type() const { return _type; }
143 QString rawUnits() const { return _rawUnits; }
144 QString cookedUnits() const { return _cookedUnits; }
145 bool vehicleRebootRequired() const { return _vehicleRebootRequired; }
146 bool qgcRebootRequired() const { return _qgcRebootRequired; }
147 bool hasControl() const { return _hasControl; }
148 bool readOnly() const { return _readOnly; }
149 bool writeOnly() const { return _writeOnly; }
150 bool volatileValue() const { return _volatile; }
151
154 double rawIncrement() const { return _rawIncrement; }
155 double cookedIncrement() const;
156
157 Translator rawTranslator() const { return _rawTranslator; }
158 Translator cookedTranslator() const { return _cookedTranslator; }
159
161 void addBitmaskInfo(const QString &name, const QVariant &value);
162
164 void addEnumInfo(const QString &name, const QVariant &value);
165
167 void removeEnumInfo(const QVariant &value);
168
169 void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; }
170 void setRawDefaultValue(const QVariant &rawDefaultValue);
171 void setBitmaskInfo(const QStringList &strings, const QVariantList &values);
172 void setEnumInfo(const QStringList &strings, const QVariantList &values);
173 void setCategory(const QString &category) { _category = category; }
174 void setGroup(const QString &group) { _group = group; }
175 void setLongDescription(const QString &longDescription) { _longDescription = longDescription;}
176 void setRawMax(const QVariant &rawMax);
177 void setRawMin(const QVariant &rawMin);
178 void setRawUserMin(const QVariant &rawUserMin);
179 void setRawUserMax(const QVariant &rawUserMax);
180 void setName(const QString &name) { _name = name; }
181 void setShortDescription(const QString &shortDescription) { _shortDescription = shortDescription; }
182 void setRawUnits(const QString &rawUnits);
183 void setVehicleRebootRequired(bool rebootRequired) { _vehicleRebootRequired = rebootRequired; }
184 void setQGCRebootRequired(bool rebootRequired) { _qgcRebootRequired = rebootRequired; }
185 void setRawIncrement(double increment) { _rawIncrement = increment; }
186 void setHasControl(bool bValue) { _hasControl = bValue; }
187 void setReadOnly(bool bValue) { _readOnly = bValue; }
188 void setWriteOnly(bool bValue) { _writeOnly = bValue; }
189 void setVolatileValue(bool bValue);
190
191 void setTranslators(Translator rawTranslator_, Translator cookedTranslator_);
192
195
202 bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const;
203
205 bool convertAndValidateCooked(const QVariant &cookedValue, bool convertOnly, QVariant &typedValue, QString &errorString) const;
206
211 bool clampValue(const QVariant &cookedValue, QVariant &typedValue) const;
212
215 void setCustomCookedValidator(CustomCookedValidator customValidator) { _customCookedValidator = customValidator; }
216
217 static constexpr int kDefaultDecimalPlaces = 3;
218 static constexpr int kUnknownDecimalPlaces = -1;
219
220 static ValueType_t stringToType(const QString &typeString, bool &unknownType);
221 static QString typeToString(ValueType_t type);
222 static size_t typeToSize(ValueType_t type);
223
224 static QVariant minForType(ValueType_t type);
225 static QVariant maxForType(ValueType_t type);
226
227 static constexpr const char *kDefaultCategory = QT_TRANSLATE_NOOP("FactMetaData", "Other");
228 static constexpr const char *kDefaultGroup = QT_TRANSLATE_NOOP("FactMetaData", "Misc");
229 static constexpr const char *qgcFileType = "FactMetaData";
230
231private:
232 QVariant _minForType() const { return minForType(_type); };
233 QVariant _maxForType() const { return maxForType(_type); };
235 void _setAppSettingsTranslators();
236
238 template<class T>
239 void clamp(QVariant& variantValue) const {
240 if (cookedMin().value<T>() > variantValue.value<T>()) {
241 variantValue = cookedMin();
242 } else if(variantValue.value<T>() > cookedMax().value<T>()) {
243 variantValue = cookedMax();
244 }
245 }
246
247 template<class T>
248 bool isInCookedLimit(const QVariant &variantValue) const {
249 return ((cookedMin().value<T>() <= variantValue.value<T>()) && (variantValue.value<T>() <= cookedMax().value<T>()));
250 }
251
252 template<class T>
253 bool isInRawLimit(const QVariant &variantValue) const {
254 return ((rawMin().value<T>() <= variantValue.value<T>()) && (variantValue.value<T>() <= rawMax().value<T>()));
255 }
256
257 bool isInRawMinLimit(const QVariant &variantValue) const;
258 bool isInRawMaxLimit(const QVariant &variantValue) const;
259
260 static bool _parseEnum(const QString& name, const QJsonObject &jsonObject, const DefineMap_t &defineMap, QStringList &rgDescriptions, QStringList &rgValues, QString &errorString);
261 static bool _parseValuesArray(const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<double> &rgValues, QString &errorString);
262 static bool _parseBitmaskArray(const QJsonObject &jsonObject, QStringList &rgDescriptions, QList<int> &rgValues, QString &errorString);
263
264 // Built in translators
265 static QVariant _defaultTranslator(const QVariant &from) { return from; }
266 static QVariant _degreesToRadians(const QVariant &degrees);
267 static QVariant _radiansToDegrees(const QVariant &radians);
268 static QVariant _centiDegreesToDegrees(const QVariant &centiDegrees);
269 static QVariant _degreesToCentiDegrees(const QVariant &degrees);
270 static QVariant _centiCelsiusToCelsius(const QVariant &centiCelsius);
271 static QVariant _celsiusToCentiCelsius(const QVariant &celsius);
272 static QVariant _userGimbalDegreesToMavlinkGimbalDegrees(const QVariant &userGimbalDegrees);
273 static QVariant _mavlinkGimbalDegreesToUserGimbalDegrees(const QVariant &mavlinkGimbalDegrees);
274 static QVariant _metersToFeet(const QVariant &meters);
275 static QVariant _feetToMeters(const QVariant &feet);
276 static QVariant _squareMetersToSquareKilometers(const QVariant &squareMeters);
277 static QVariant _squareKilometersToSquareMeters(const QVariant &squareKilometers);
278 static QVariant _squareMetersToHectares(const QVariant &squareMeters);
279 static QVariant _hectaresToSquareMeters(const QVariant &hectares);
280 static QVariant _squareMetersToSquareFeet(const QVariant &squareMeters);
281 static QVariant _squareFeetToSquareMeters(const QVariant &squareFeet);
282 static QVariant _squareMetersToAcres(const QVariant &squareMeters);
283 static QVariant _acresToSquareMeters(const QVariant &acres);
284 static QVariant _squareMetersToSquareMiles(const QVariant &squareMeters);
285 static QVariant _squareMilesToSquareMeters(const QVariant &squareMiles);
286 static QVariant _metersPerSecondToMilesPerHour(const QVariant &metersPerSecond);
287 static QVariant _milesPerHourToMetersPerSecond(const QVariant &milesPerHour);
288 static QVariant _metersPerSecondToKilometersPerHour(const QVariant &metersPerSecond);
289 static QVariant _kilometersPerHourToMetersPerSecond(const QVariant &kilometersPerHour);
290 static QVariant _metersPerSecondToKnots(const QVariant &metersPerSecond);
291 static QVariant _knotsToMetersPerSecond(const QVariant &knots);
292 static QVariant _percentToNorm(const QVariant &percent);
293 static QVariant _normToPercent(const QVariant &normalized);
294 static QVariant _centimetersToInches(const QVariant &centimeters);
295 static QVariant _inchesToCentimeters(const QVariant &inches);
296 static QVariant _celsiusToFarenheit(const QVariant &celsius);
297 static QVariant _farenheitToCelsius(const QVariant &farenheit);
298 static QVariant _kilogramsToGrams(const QVariant &kg);
299 static QVariant _ouncesToGrams(const QVariant &oz);
300 static QVariant _poundsToGrams(const QVariant &lbs);
301 static QVariant _gramsToKilograms(const QVariant &g);
302 static QVariant _gramsToOunces(const QVariant &g);
303 static QVariant _gramsToPunds(const QVariant &g);
304
305 enum UnitTypes {
306 UnitHorizontalDistance = 0,
307 UnitVerticalDistance,
308 UnitArea,
309 UnitSpeed,
310 UnitTemperature,
311 UnitWeight
312 };
313
314 struct AppSettingsTranslation_s {
315 QString rawUnits;
316 const char *cookedUnits = nullptr;
317 UnitTypes unitType = UnitHorizontalDistance;
318 uint32_t unitOption = 0;
319 Translator rawTranslator;
320 Translator cookedTranslator;
321 };
322
323 static const AppSettingsTranslation_s *_findAppSettingsUnitsTranslation(const QString &rawUnits, UnitTypes type);
324
325 static void _loadJsonDefines(const QJsonObject &jsonDefinesObject, QMap<QString, QString> &defineMap);
326
327 ValueType_t _type = valueTypeInt32; // must be first for correct constructor init
328 int _decimalPlaces = kUnknownDecimalPlaces;
329 QVariant _rawDefaultValue = 0;
330 bool _defaultValueAvailable = false;
331 QStringList _bitmaskStrings;
332 QVariantList _bitmaskValues;
333 QStringList _enumStrings;
334 QVariantList _enumValues;
335 QString _category = kDefaultCategory;
336 QString _group = kDefaultGroup;
337 QString _longDescription;
338 QVariant _rawMax = _maxForType();
339 QVariant _rawMin = _minForType();
340 QVariant _rawUserMin; // Specifically left as unset by default to indicate no user min
341 QVariant _rawUserMax; // Specifically left as unset by default to indicate no user max
342 QString _name;
343 QString _shortDescription;
344 QString _rawUnits;
345 QString _cookedUnits;
346 Translator _rawTranslator = _defaultTranslator;
347 Translator _cookedTranslator = _defaultTranslator;
348 bool _vehicleRebootRequired = false;
349 bool _qgcRebootRequired = false;
350 double _rawIncrement = std::numeric_limits<double>::quiet_NaN();
351 bool _hasControl = true;
352 bool _readOnly = false;
353 bool _writeOnly = false;
354 bool _volatile = false;
355 CustomCookedValidator _customCookedValidator = nullptr;
356
357 // Exact conversion constants
358 static constexpr struct UnitConsts_s {
359 static constexpr const qreal secondsPerHour = 3600.0;
360 static constexpr const qreal knotsToKPH = 1.852;
361 static constexpr const qreal milesToMeters = 1609.344;
362 static constexpr const qreal feetToMeters = 0.3048;
363 static constexpr const qreal inchesToCentimeters = 2.54;
364 static constexpr const qreal ouncesToGrams = 28.3495;
365 static constexpr const qreal poundsToGrams = 453.592;
366 static constexpr const qreal acresToSquareMeters = 4046.86;
367 static constexpr const qreal squareMetersToAcres = 0.000247105;
368 static constexpr const qreal feetToSquareMeters = 0.0929;
369 static constexpr const qreal squareMetersToSquareFeet = 10.7639;
370 static constexpr const qreal squareMetersToSquareMiles = 3.86102e-7;
371 static constexpr const qreal squareMilesToSquareMeters = 2589988.11;
372 } constants{};
373
374 struct BuiltInTranslation_s {
375 QString rawUnits;
376 const char *cookedUnits;
377 Translator rawTranslator;
378 Translator cookedTranslator;
379 };
380
381 static const BuiltInTranslation_s _rgBuiltInTranslations[];
382 static const AppSettingsTranslation_s _rgAppSettingsTranslations[];
383
384 static constexpr const char *_jsonMetaDataDefinesName = "QGC.MetaData.Defines";
385 static constexpr const char *_jsonMetaDataFactsName = "QGC.MetaData.Facts";
386 static constexpr const char *_enumStringsJsonKey = "enumStrings";
387 static constexpr const char *_enumValuesJsonKey = "enumValues";
388
389 // This is the newer json format for enums and bitmasks. They are used by the new COMPONENT_METADATA parameter metadata for example.
390 static constexpr const char *_enumValuesArrayJsonKey = "values";
391 static constexpr const char *_enumBitmaskArrayJsonKey = "bitmask";
392 static constexpr const char *_enumValuesArrayValueJsonKey = "value";
393 static constexpr const char *_enumValuesArrayDescriptionJsonKey = "description";
394 static constexpr const char *_enumBitmaskArrayIndexJsonKey = "index";
395 static constexpr const char *_enumBitmaskArrayDescriptionJsonKey = "description";
396
397 static constexpr const char *_rgKnownTypeStrings[] = {
398 "Uint8",
399 "Int8",
400 "Uint16",
401 "Int16",
402 "Uint32",
403 "Int32",
404 "Uint64",
405 "Int64",
406 "Float",
407 "Double",
408 "String",
409 "Bool",
410 "ElapsedSeconds",
411 "Custom",
412 };
413
414 static constexpr const ValueType_t _rgKnownValueTypes[] = {
429 };
430
431 static constexpr const char *_decimalPlacesJsonKey = "decimalPlaces";
432 static constexpr const char *_nameJsonKey = "name";
433 static constexpr const char *_typeJsonKey = "type";
434 static constexpr const char *_shortDescriptionJsonKey = "shortDesc";
435 static constexpr const char *_longDescriptionJsonKey = "longDesc";
436 static constexpr const char *_unitsJsonKey = "units";
437 static constexpr const char *_defaultValueJsonKey = "default";
438 static constexpr const char *_mobileDefaultValueJsonKey = "mobileDefault";
439 static constexpr const char *_minJsonKey = "min";
440 static constexpr const char *_maxJsonKey = "max";
441 static constexpr const char *_userMinJsonKey = "userMin";
442 static constexpr const char *_userMaxJsonKey = "userMax";
443 static constexpr const char *_incrementJsonKey = "increment";
444 static constexpr const char *_hasControlJsonKey = "control";
445 static constexpr const char *_qgcRebootRequiredJsonKey = "qgcRebootRequired";
446 static constexpr const char *_rebootRequiredJsonKey = "rebootRequired";
447 static constexpr const char *_categoryJsonKey = "category";
448 static constexpr const char *_groupJsonKey = "group";
449 static constexpr const char *_volatileJsonKey = "volatile";
450};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
QString errorString
static FactMetaData * createFromJsonObject(const QJsonObject &json, const QMap< QString, QString > &defineMap, QObject *metaDataParent)
void setRawUnits(const QString &rawUnits)
void setDecimalPlaces(int decimalPlaces)
void setHasControl(bool bValue)
QStringList enumStrings() const
static constexpr const char * qgcFileType
QVariant cookedDefaultValue() const
void setRawUserMin(const QVariant &rawUserMin)
static QVariant appSettingsAreaUnitsToSquareMeters(const QVariant &area)
Converts from user specified distance unit to meters.
static QVariant metersToAppSettingsVerticalDistanceUnits(const QVariant &meters)
Converts from meters to the user specified vertical distance unit.
bool hasControl() const
void setShortDescription(const QString &shortDescription)
QVariant cookedMin() const
static QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant &meters)
Converts from meters to the user specified horizontal distance unit.
QStringList bitmaskStrings() const
static QVariant metersSecondToAppSettingsSpeedUnits(const QVariant &metersSecond)
Converts from meters/second to the user specified speed unit.
bool clampValue(const QVariant &cookedValue, QVariant &typedValue) const
bool qgcRebootRequired() const
bool convertAndValidateCooked(const QVariant &cookedValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
Same as convertAndValidateRaw except for cookedValue input.
QVariant cookedUserMax() const
void setQGCRebootRequired(bool rebootRequired)
static size_t typeToSize(ValueType_t type)
Translator cookedTranslator() const
QVariant cookedMax() const
static QStringList splitTranslatedList(const QString &translatedList)
static QString typeToString(ValueType_t type)
QString group() const
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
QVariant rawMin() const
@ valueTypeElapsedTimeInSeconds
static constexpr const char * kDefaultGroup
void setName(const QString &name)
QVariantList enumValues() const
void addBitmaskInfo(const QString &name, const QVariant &value)
Used to add new values to the bitmask lists after the meta data has been loaded.
void setLongDescription(const QString &longDescription)
static QMap< QString, FactMetaData * > createMapFromJsonArray(const QJsonArray &jsonArray, const DefineMap_t &defineMap, QObject *metaDataParent)
QString cookedUnits() const
QString shortDescription() const
static QString appSettingsVerticalDistanceUnitsString()
Returns the string for vertical distance units which has configued by user.
void setRawUserMax(const QVariant &rawUserMax)
bool maxIsDefaultForType() const
static constexpr int kUnknownDecimalPlaces
Number of decimal places to specify is not known.
static constexpr const char * kDefaultCategory
int decimalPlaces() const
void setVehicleRebootRequired(bool rebootRequired)
static constexpr int kDefaultDecimalPlaces
Default value for decimal places if not specified/known.
static QString appSettingsWeightUnitsString()
Returns the string for weight units which has configued by user.
void setTranslators(Translator rawTranslator_, Translator cookedTranslator_)
void setRawMin(const QVariant &rawMin)
QVariant cookedUserMin() const
QVariant rawUserMin() const
void setCategory(const QString &category)
bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
QString rawUnits() const
QVariant rawUserMax() const
static const QString defaultCategory()
QString(* CustomCookedValidator)(const QVariant &cookedValue)
static QString appSettingsAreaUnitsString()
Returns the string for distance units which has configued by user.
static QVariant maxForType(ValueType_t type)
void setWriteOnly(bool bValue)
void setRawDefaultValue(const QVariant &rawDefaultValue)
static const QString defaultGroup()
static QVariant gramsToAppSettingsWeightUnits(const QVariant &grams)
Converts from grams to the user specified weight unit.
static QString appSettingsHorizontalDistanceUnitsString()
Returns the string for horizontal distance units which has configued by user.
double rawIncrement() const
void setEnumInfo(const QStringList &strings, const QVariantList &values)
void setBitmaskInfo(const QStringList &strings, const QVariantList &values)
void setRawMax(const QVariant &rawMax)
bool readOnly() const
static QVariant squareMetersToAppSettingsAreaUnits(const QVariant &squareMeters)
Converts from meters to the user specified distance unit.
QString category() const
void removeEnumInfo(const QVariant &value)
Used to remove values from the enum lists after the meta data has been loaded.
QVariant(* Translator)(const QVariant &from)
static QVariant minForType(ValueType_t type)
static QVariant appSettingsVerticalDistanceUnitsToMeters(const QVariant &distance)
Converts from user specified vertical distance unit to meters.
QString longDescription() const
bool minIsDefaultForType() const
void setRawIncrement(double increment)
bool writeOnly() const
void addEnumInfo(const QString &name, const QVariant &value)
Used to add new values to the enum lists after the meta data has been loaded.
void setVolatileValue(bool bValue)
QString name() const
static QVariant appSettingsHorizontalDistanceUnitsToMeters(const QVariant &distance)
Converts from user specified horizontal distance unit to meters.
void setGroup(const QString &group)
QVariantList bitmaskValues() const
QVariant rawDefaultValue() const
QMap< QString, FactMetaData * > NameToMetaDataMap_t
ValueType_t type() const
static ValueType_t stringToType(const QString &typeString, bool &unknownType)
static QVariant appSettingsSpeedUnitsToMetersSecond(const QVariant &speed)
Converts from user specified speed unit to meters/second.
void setCustomCookedValidator(CustomCookedValidator customValidator)
static QVariant appSettingsWeightUnitsToGrams(const QVariant &weight)
Converts from user specified weight unit to grams.
bool vehicleRebootRequired() const
bool volatileValue() const
QVariant rawMax() const
bool defaultValueAvailable() const
double cookedIncrement() const
void setBuiltInTranslator()
Set the translators to the standard built in versions.
QMap< QString, QString > DefineMap_t
static QString appSettingsSpeedUnitsString()
Returns the string for speed units which has configued by user.
void setReadOnly(bool bValue)
Translator rawTranslator() const
Provides access to all app settings.