QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Fact.cc
Go to the documentation of this file.
1#include "Fact.h"
3#include "AppMessages.h"
4#include "QGCApplication.h"
5#include "QGCCorePlugin.h"
7#include "SettingsManager.h"
8
9QGC_LOGGING_CATEGORY(FactLog, "FactSystem.Fact")
10
11Fact::Fact(QObject *parent)
12 : QObject(parent)
13{
14 // qCDebug(FactLog) << Q_FUNC_INFO << this;
15
16 FactMetaData *const metaData = new FactMetaData(_type, this);
17 setMetaData(metaData);
18
19 _init();
20}
21
22Fact::Fact(int componentId, const QString &name, FactMetaData::ValueType_t type, QObject *parent)
23 : QObject(parent)
24 , _name(name)
25 , _componentId(componentId)
26 , _type(type)
27{
28 // qCDebug(FactLog) << Q_FUNC_INFO << this;
29
30 FactMetaData *const metaData = new FactMetaData(_type, this);
32
33 _init();
34}
35
36Fact::Fact(const QString& settingsGroup, FactMetaData *metaData, QObject *parent)
37 : QObject(parent)
38 , _name(metaData->name())
39 , _componentId(0)
40 , _type(metaData->type())
41{
42 // qCDebug(FactLog) << Q_FUNC_INFO << this;
43
44 bool visible = true;
45 SettingsManager::adjustSettingMetaData(settingsGroup, *metaData, visible);
46 setMetaData(metaData, true /* setDefaultFromMetaData */);
47
48 if (!QGC::runningUnitTests()) {
49 if (metaData->defaultValueAvailable() && !visible) {
50 // If setting is not visible, we force to default value
51 const QVariant defaultValue = metaData->rawDefaultValue();
52 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
53 _rawValue = defaultValue;
54 }
55 }
56
57 _init();
58}
59
60Fact::Fact(const Fact &other, QObject *parent)
61 : QObject(parent)
62{
63 // qCDebug(FactLog) << Q_FUNC_INFO << this;
64
65 *this = other;
66
67 _init();
68}
69
71{
72 // qCDebug(FactLog) << Q_FUNC_INFO << this;
73}
74
75void Fact::_init()
76{
77 (void) connect(this, &Fact::containerRawValueChanged, this, &Fact::_checkForRebootMessaging);
78}
79
80const Fact &Fact::operator=(const Fact& other)
81{
82 if (this == &other) {
83 return *this;
84 }
85
86 QMutexLocker<QRecursiveMutex> otherLocker(&other._rawValueMutex);
87 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
88
89 _name = other._name;
91 _rawValue = other._rawValue;
92 _type = other._type;
95 _valueSliderModel = nullptr;
96 if (_metaData && other._metaData) {
97 *_metaData = *other._metaData;
98 } else {
99 _metaData = nullptr;
100 }
101
102 return *this;
103}
104
105void Fact::forceSetRawValue(const QVariant &value)
106{
107 if (_metaData) {
108 QVariant typedValue;
109 QString errorString;
110
111 if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
112 {
113 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
114 _rawValue = typedValue;
115 }
116
117 const QVariant cooked = _metaData->rawTranslator()(typedValue);
119 //-- Must be in this order
120 emit containerRawValueChanged(typedValue);
121 emit rawValueChanged(typedValue);
122 }
123 } else {
124 qCWarning(FactLog) << kMissingMetadata << name();
125 }
126}
127
128void Fact::setRawValue(const QVariant &value)
129{
130 if (_metaData) {
131 QVariant typedValue;
132 QString errorString;
133
134 if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
135 bool changed = false;
136 {
137 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
138 if (typedValue != _rawValue) {
139 _rawValue = typedValue;
140 changed = true;
141 }
142 }
143
144 if (changed) {
145 const QVariant cooked = _metaData->rawTranslator()(typedValue);
147 //-- Must be in this order
148 emit containerRawValueChanged(typedValue);
149 emit rawValueChanged(typedValue);
150 }
151 }
152 } else {
153 qCWarning(FactLog) << kMissingMetadata << name();
154 }
155}
156
157void Fact::setCookedValue(const QVariant& value)
158{
159 if (_metaData) {
161 } else {
162 qCWarning(FactLog) << kMissingMetadata << name();
163 }
164}
165
166int Fact::valueIndex(const QString &value) const
167{
168 if (_metaData) {
169 return _metaData->enumStrings().indexOf(value);
170 }
171 qCWarning(FactLog) << kMissingMetadata << name();
172 return -1;
173}
174
175void Fact::setEnumStringValue(const QString &value)
176{
177 const int index = valueIndex(value);
178 if (index != -1) {
180 }
181}
182
183void Fact::setEnumIndex(int index)
184{
185 if (_metaData) {
187 } else {
188 qCWarning(FactLog) << kMissingMetadata << name();
189 }
190}
191
192void Fact::containerSetRawValue(const QVariant &value)
193{
194 QVariant cooked;
195 QVariant currentRaw = value;
196 bool changed = false;
197 {
198 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
199 if (_rawValue != value) {
200 _rawValue = value;
201 changed = true;
202 }
203 currentRaw = _rawValue;
204 if (_metaData) {
205 cooked = _metaData->rawTranslator()(_rawValue);
206 } else {
207 cooked = _rawValue;
208 }
209 }
210
211 if (changed) {
213 emit rawValueChanged(currentRaw);
214 }
215
216 // This always need to be signalled in order to support forceSetRawValue usage and waiting for vehicleUpdated signal
217 emit vehicleUpdated(currentRaw);
218}
219
220QVariant Fact::cookedValue() const
221{
222 QMutexLocker<QRecursiveMutex> locker(&_rawValueMutex);
223 if (_metaData) {
225 }
226
227 qCWarning(FactLog) << kMissingMetadata << name();
228 return _rawValue;
229}
230
232{
233 if (_metaData) {
234 const int enumIndex = this->enumIndex();
235 if ((enumIndex >= 0) && (enumIndex < _metaData->enumStrings().count())) {
237 }
238 } else {
239 qCWarning(FactLog) << kMissingMetadata << name();
240 }
241
242 return QString();
243}
244
246{
247 if (_metaData) {
248 //-- Only enums have an index
249 if (!_metaData->enumValues().isEmpty()) {
250 int index = 0;
251 for (const QVariant &enumValue: _metaData->enumValues()) {
252 if (enumValue == rawValue()) {
253 return index;
254 }
255 //-- Float comparisons don't always work
257 const double diff = fabs(enumValue.toDouble() - rawValue().toDouble());
258 static constexpr double accuracy = 1.0 / 1000000.0;
259 if (diff < accuracy) {
260 return index;
261 }
262 }
263 index++;
264 }
265 // Current value is not in list, add it manually
266 _metaData->addEnumInfo(tr("Unknown: %1").arg(rawValue().toString()), rawValue());
267 emit enumsChanged();
268 return index;
269 }
270 } else {
271 qCWarning(FactLog) << kMissingMetadata << name();
272 }
273 return -1;
274}
275
276QStringList Fact::enumStrings() const
277{
278 if (_metaData) {
279 return _metaData->enumStrings();
280 } else {
281 qCWarning(FactLog) << kMissingMetadata << name();
282 return QStringList();
283 }
284}
285
286QVariantList Fact::enumValues() const
287{
288 if (_metaData) {
289 return _metaData->enumValues();
290 } else {
291 qCWarning(FactLog) << kMissingMetadata << name();
292 return QVariantList();
293 }
294}
295
296void Fact::setEnumInfo(const QStringList &strings, const QVariantList &values)
297{
298 if (_metaData) {
299 _metaData->setEnumInfo(strings, values);
300 emit enumsChanged();
301 } else {
302 qCWarning(FactLog) << kMissingMetadata << name();
303 }
304}
305
306QStringList Fact::bitmaskStrings() const
307{
308 if (_metaData) {
309 return _metaData->bitmaskStrings();
310 } else {
311 qCWarning(FactLog) << kMissingMetadata << name();
312 return QStringList();
313 }
314}
315
316QVariantList Fact::bitmaskValues() const
317{
318 if (_metaData) {
319 return _metaData->bitmaskValues();
320 } else {
321 qCWarning(FactLog) << kMissingMetadata << name();
322 return QVariantList();
323 }
324}
325
327{
328 if (_metaData) {
329 const auto values = _metaData->bitmaskValues();
330 const auto strings = _metaData->bitmaskStrings();
331 if (values.size() != strings.size()) {
332 qCWarning(FactLog) << "Size of bitmask value and string is different." << name();
333 return {};
334 }
335
336 QStringList selected;
337 for (qsizetype i = 0; i < values.size(); i++) {
338 if (rawValue().toInt() & values[i].toInt()) {
339 selected += strings[i];
340 }
341 }
342
343 if (selected.isEmpty()) {
344 selected += "Not value selected";
345 }
346
347 return selected;
348 } else {
349 qCWarning(FactLog) << kMissingMetadata << name();
350 return {};
351 }
352}
353
354QString Fact::_variantToString(const QVariant &variant, int decimalPlaces) const
355{
356 QString valueString;
357
358 const auto stripNegativeZero = [](QString &candidate) {
359 static const QRegularExpression reNegativeZero(QStringLiteral("^-0\\.0+$"));
360 const auto match = reNegativeZero.match(candidate);
361 if (match.hasMatch() || candidate == QStringLiteral("-0")) {
362 candidate = candidate.mid(1);
363 }
364 };
365
366 switch (type()) {
368 {
369 const float fValue = variant.toFloat();
370 if (qIsNaN(fValue)) {
371 valueString = invalidValueString(decimalPlaces);
372 } else {
373 valueString = QStringLiteral("%1").arg(fValue, 0, 'f', decimalPlaces);
374 stripNegativeZero(valueString);
375 }
376 }
377 break;
379 {
380 const double dValue = variant.toDouble();
381 if (qIsNaN(dValue)) {
382 valueString = invalidValueString(decimalPlaces);
383 } else {
384 valueString = QStringLiteral("%1").arg(dValue, 0, 'f', decimalPlaces);
385 stripNegativeZero(valueString);
386 }
387 break;
388 }
390 valueString = variant.toBool() ? tr("true") : tr("false");
391 break;
393 {
394 const double dValue = variant.toDouble();
395 if (qIsNaN(dValue)) {
396 valueString = invalidValueString(decimalPlaces);
397 } else {
398 QTime time(0, 0, 0, 0);
399 time = time.addSecs(dValue);
400 valueString = time.toString(QStringLiteral("hh:mm:ss"));
401 }
402 break;
403 }
404 default:
405 valueString = variant.toString();
406 break;
407 }
408
409 return valueString;
410}
411
412QString Fact::invalidValueString(int decimalPlaces) const {
413 switch (type()) {
416 if (decimalPlaces <= 0) {
417 return QStringLiteral("–");
418 }
419 return QStringLiteral("–.") +
420 QString(decimalPlaces, QChar(u'–'));
422 return QStringLiteral("––:––:––");
423 default:
424 return QStringLiteral("–");
425 }
426}
427
429{
430 return _variantToString(rawValue(), 18);
431}
432
433QString Fact::rawValueString() const
434{
436}
437
439{
441}
442
443QVariant Fact::rawDefaultValue() const
444{
445 if (_metaData) {
447 qCDebug(FactLog) << "Access to unavailable default value";
448 }
449 return _metaData->rawDefaultValue();
450 } else {
451 qCWarning(FactLog) << kMissingMetadata << name();
452 return QVariant(0);
453 }
454}
455
457{
458 if (_metaData) {
460 qCDebug(FactLog) << "Access to unavailable default value";
461 }
463 } else {
464 qCWarning(FactLog) << kMissingMetadata << name();
465 return QVariant(0);
466 }
467}
468
473
475{
476 if (_metaData) {
477 return _metaData->shortDescription();
478 } else {
479 qCWarning(FactLog) << kMissingMetadata << name();
480 return QString();
481 }
482}
483
484QString Fact::label() const
485{
486 if (_metaData) {
487 return _metaData->label();
488 } else {
489 qCWarning(FactLog) << kMissingMetadata << name();
490 return QString();
491 }
492}
493
495{
496 if (_metaData) {
497 return _metaData->longDescription();
498 } else {
499 qCWarning(FactLog) << kMissingMetadata << name();
500 return QString();
501 }
502}
503
504QString Fact::rawUnits() const
505{
506 if (_metaData) {
507 return _metaData->rawUnits();
508 } else {
509 qCWarning(FactLog) << kMissingMetadata << name();
510 return QString();
511 }
512}
513
514QString Fact::cookedUnits() const
515{
516 if (_metaData) {
517 return _metaData->cookedUnits();
518 } else {
519 qCWarning(FactLog) << kMissingMetadata << name();
520 return QString();
521 }
522}
523
524QVariant Fact::rawMin() const
525{
526 if (_metaData) {
527 return _metaData->rawMin();
528 } else {
529 qCWarning(FactLog) << kMissingMetadata << name();
530 return QVariant(0);
531 }
532}
533
534QVariant Fact::cookedMin() const
535{
536 if (_metaData) {
537 return _metaData->cookedMin();
538 } else {
539 qCWarning(FactLog) << kMissingMetadata << name();
540 return QVariant(0);
541 }
542}
543
544QVariant Fact::rawUserMin() const
545{
546 if (_metaData) {
547 return _metaData->rawUserMin();
548 }
549
550 qCWarning(FactLog) << kMissingMetadata << name();
551 return QVariant(0);
552}
553
554QVariant Fact::cookedUserMin() const
555{
556 if (_metaData) {
557 return _metaData->cookedUserMin();
558 }
559
560 qCWarning(FactLog) << kMissingMetadata << name();
561 return QVariant(0);
562}
563
565{
567}
568
570{
572}
573
574QVariant Fact::rawMax() const
575{
576 if (_metaData) {
577 return _metaData->rawMax();
578 } else {
579 qCWarning(FactLog) << kMissingMetadata << name();
580 return QVariant(0);
581 }
582}
583
584QVariant Fact::cookedMax() const
585{
586 if (_metaData) {
587 return _metaData->cookedMax();
588 } else {
589 qCWarning(FactLog) << kMissingMetadata << name();
590 return QVariant(0);
591 }
592}
593
594QVariant Fact::rawUserMax() const
595{
596 if (_metaData) {
597 return _metaData->rawUserMax();
598 }
599
600 qCWarning(FactLog) << kMissingMetadata << name();
601 return QVariant(0);
602}
603
604QVariant Fact::cookedUserMax() const
605{
606 if (_metaData) {
607 return _metaData->cookedUserMax();
608 }
609
610 qCWarning(FactLog) << kMissingMetadata << name();
611 return QVariant(0);
612}
613
615{
617}
618
620{
622}
623
625{
626 if (_metaData) {
628 } else {
629 qCWarning(FactLog) << kMissingMetadata << name();
630 return false;
631 }
632}
633
635{
636 if (_metaData) {
638 } else {
639 qCWarning(FactLog) << kMissingMetadata << name();
640 return false;
641 }
642}
643
645{
646 if (_metaData) {
647 return _metaData->decimalPlaces();
648 } else {
649 qCWarning(FactLog) << kMissingMetadata << name();
651 }
652}
653
654QString Fact::category() const
655{
656 if (_metaData) {
657 return _metaData->category();
658 } else {
659 qCWarning(FactLog) << kMissingMetadata << name();
660 return QString();
661 }
662}
663
664QString Fact::group() const
665{
666 if (_metaData) {
667 return _metaData->group();
668 } else {
669 qCWarning(FactLog) << kMissingMetadata << name();
670 return QString();
671 }
672}
673
674void Fact::setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData)
675{
677 if (setDefaultFromMetaData && metaData->defaultValueAvailable()) {
679 }
681}
682
684{
685 if (_metaData) {
687 return _metaData->rawDefaultValue() == rawValue();
688 } else {
689 return false;
690 }
691 } else {
692 qCWarning(FactLog) << kMissingMetadata << name();
693 return false;
694 }
695}
696
698{
699 if (_metaData) {
701 } else {
702 qCWarning(FactLog) << kMissingMetadata << name();
703 return false;
704 }
705}
706
707QString Fact::validate(const QString &cookedValue, bool convertOnly)
708{
709 if (_metaData) {
710 QVariant typedValue;
711 QString errorString;
712
713 _metaData->convertAndValidateCooked(cookedValue, convertOnly, typedValue, errorString);
714
715 return errorString;
716 } else {
717 qCWarning(FactLog) << kMissingMetadata << name();
718 return QStringLiteral("Internal error: Meta data pointer missing");
719 }
720}
721
722QVariant Fact::clamp(const QString &cookedValue)
723{
724 if (_metaData) {
725 QVariant typedValue;
726 if (_metaData->clampValue(cookedValue, typedValue)) {
727 return typedValue;
728 } else {
729 //-- If conversion failed, return current value
730 return rawValue();
731 }
732 } else {
733 qCWarning(FactLog) << kMissingMetadata << name();
734 }
735 return QVariant();
736}
737
739{
740 if (_metaData) {
742 } else {
743 qCWarning(FactLog) << kMissingMetadata << name();
744 return false;
745 }
746}
747
749{
750 if (_metaData) {
752 } else {
753 qCWarning(FactLog) << kMissingMetadata << name();
754 return false;
755 }
756}
757
765
766void Fact::_sendValueChangedSignal(const QVariant &value)
767{
769 emit valueChanged(value);
771 } else {
773 }
774}
775
783
785{
786 if (_metaData) {
787 if (_metaData->enumStrings().count()) {
788 return enumStringValue();
789 } else {
790 return cookedValueString();
791 }
792 } else {
793 qCWarning(FactLog) << kMissingMetadata << name();
794 }
795 return QString();
796}
797
798double Fact::rawIncrement() const
799{
800 if (_metaData) {
801 return _metaData->rawIncrement();
802 } else {
803 qCWarning(FactLog) << kMissingMetadata << name();
804 }
805 return std::numeric_limits<double>::quiet_NaN();
806}
807
809{
810 if (_metaData) {
811 return _metaData->cookedIncrement();
812 } else {
813 qCWarning(FactLog) << kMissingMetadata << name();
814 }
815 return std::numeric_limits<double>::quiet_NaN();
816}
817
819{
820 if (_metaData) {
821 return _metaData->hasControl();
822 } else {
823 qCWarning(FactLog) << kMissingMetadata << name();
824 return false;
825 }
826}
827
828bool Fact::readOnly() const
829{
830 if (_metaData) {
831 return _metaData->readOnly();
832 } else {
833 qCWarning(FactLog) << kMissingMetadata << name();
834 return false;
835 }
836}
837
838bool Fact::writeOnly() const
839{
840 if (_metaData) {
841 return _metaData->writeOnly();
842 } else {
843 qCWarning(FactLog) << kMissingMetadata << name();
844 return false;
845 }
846}
847
849{
850 if (_metaData) {
851 return _metaData->volatileValue();
852 } else {
853 qCWarning(FactLog) << kMissingMetadata << name();
854 return false;
855 }
856}
857
866
867void Fact::_checkForRebootMessaging()
868{
869 if (qgcApp()) {
870 if (!QGC::runningUnitTests()) {
871 if (vehicleRebootRequired()) {
872 QGC::showRebootAppMessage(tr("Reboot vehicle for changes to take effect."));
873 } else if (qgcRebootRequired()) {
874 QGC::showRebootAppMessage(tr("Restart application for changes to take effect."));
875 }
876 }
877 }
878}
#define qgcApp()
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Holds the meta data associated with a Fact.
QString label() const
QStringList enumStrings() const
QVariant cookedDefaultValue() const
bool hasControl() const
QVariant cookedMin() const
QStringList bitmaskStrings() const
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
Translator cookedTranslator() const
QVariant cookedMax() const
QString group() const
QVariant rawMin() const
@ valueTypeElapsedTimeInSeconds
QVariantList enumValues() const
QString cookedUnits() const
QString shortDescription() const
bool maxIsDefaultForType() const
int decimalPlaces() const
static constexpr int kDefaultDecimalPlaces
Default value for decimal places if not specified/known.
QVariant cookedUserMin() const
QVariant rawUserMin() const
bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
QString rawUnits() const
QVariant rawUserMax() const
double rawIncrement() const
void setEnumInfo(const QStringList &strings, const QVariantList &values)
bool readOnly() const
QString category() const
QString longDescription() const
bool minIsDefaultForType() const
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.
QVariantList bitmaskValues() const
QVariant rawDefaultValue() const
bool vehicleRebootRequired() const
bool volatileValue() const
QVariant rawMax() const
bool defaultValueAvailable() const
double cookedIncrement() const
Translator rawTranslator() const
Provides a list model of values for incrementing/decrementing the value of a Fact.
A Fact is used to hold a single value within the system.
Definition Fact.h:17
bool _sendValueChangedSignals
Definition Fact.h:208
QString _name
Definition Fact.h:202
QStringList bitmaskStrings() const
Definition Fact.cc:306
bool writeOnly() const
Definition Fact.cc:838
int valueIndex(const QString &value) const
Definition Fact.cc:166
Q_INVOKABLE FactValueSliderListModel * valueSliderModel()
Definition Fact.cc:858
int enumIndex()
Definition Fact.cc:245
QString enumOrValueString()
Definition Fact.cc:784
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
Definition Fact.cc:674
QStringList selectedBitmaskStrings() const
Provide a list of selected strings based on the fact value with the bitmaskString/bitmaskValues map.
Definition Fact.cc:326
QString cookedUnits() const
Definition Fact.cc:514
bool qgcRebootRequired() const
Definition Fact.cc:748
QString longDescription() const
Definition Fact.cc:494
Fact(QObject *parent=nullptr)
Definition Fact.cc:11
virtual ~Fact()
Definition Fact.cc:70
bool _deferredValueChangeSignal
Definition Fact.h:209
QVariant cookedValue() const
Definition Fact.cc:220
void sendValueChangedSignalsChanged(bool sendValueChangedSignals)
QString shortDescription() const
Definition Fact.cc:474
void containerSetRawValue(const QVariant &value)
Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
Definition Fact.cc:192
FactMetaData * _metaData
Definition Fact.h:207
QVariantList enumValues() const
Definition Fact.cc:286
QString cookedMaxString() const
Definition Fact.cc:614
FactMetaData * metaData()
Definition Fact.h:171
QVariant rawDefaultValue() const
Definition Fact.cc:443
bool valueEqualsDefault() const
Definition Fact.cc:683
FactMetaData::ValueType_t _type
Definition Fact.h:206
double rawIncrement() const
Definition Fact.cc:798
bool maxIsDefaultForType() const
Definition Fact.cc:634
bool readOnly() const
Definition Fact.cc:828
QString cookedMinString() const
Definition Fact.cc:564
QString cookedUserMinString() const
Definition Fact.cc:569
void setEnumInfo(const QStringList &strings, const QVariantList &values)
Generally this is done during parsing. But if you know what you are doing, you can.
Definition Fact.cc:296
void sendDeferredValueChangedSignal()
Definition Fact.cc:776
QVariant cookedUserMax() const
Definition Fact.cc:604
QString invalidValueString() const
Definition Fact.h:128
void rawValueChanged(const QVariant &value)
QRecursiveMutex _rawValueMutex
Definition Fact.h:205
QString cookedUserMaxString() const
Definition Fact.cc:619
static constexpr const char * kMissingMetadata
Definition Fact.h:212
QString group() const
Definition Fact.cc:664
FactMetaData::ValueType_t type() const
Definition Fact.h:124
void setSendValueChangedSignals(bool sendValueChangedSignals)
Definition Fact.cc:758
QVariant cookedUserMin() const
Definition Fact.cc:554
QString cookedDefaultValueString() const
Definition Fact.cc:469
const Fact & operator=(const Fact &other)
Definition Fact.cc:80
QVariant cookedMin() const
Definition Fact.cc:534
double cookedIncrement() const
Definition Fact.cc:808
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QString rawValueString() const
Definition Fact.cc:433
void setEnumIndex(int index)
Definition Fact.cc:183
bool sendValueChangedSignals() const
Definition Fact.h:158
bool defaultValueAvailable() const
Definition Fact.cc:697
QVariant rawUserMax() const
Definition Fact.cc:594
bool volatileValue() const
Definition Fact.cc:848
QVariant rawMax() const
Definition Fact.cc:574
void forceSetRawValue(const QVariant &value)
Sets and sends new value to vehicle even if value is the same.
Definition Fact.cc:105
int decimalPlaces() const
Definition Fact.cc:644
QStringList enumStrings() const
Definition Fact.cc:276
QString cookedValueString() const
Definition Fact.cc:438
QString name() const
Definition Fact.h:121
void containerRawValueChanged(const QVariant &value)
This signal is meant for use by Fact container implementations. Used to send changed values to vehicl...
QString rawValueStringFullPrecision() const
Returns the values as a string with full 18 digit precision if float/double.
Definition Fact.cc:428
QVariantList bitmaskValues() const
Definition Fact.cc:316
QVariant cookedMax() const
Definition Fact.cc:584
QVariant rawMin() const
Definition Fact.cc:524
Q_INVOKABLE QString validate(const QString &cookedValue, bool convertOnly)
Definition Fact.cc:707
void setEnumStringValue(const QString &value)
Definition Fact.cc:175
int _componentId
Definition Fact.h:203
QString rawUnits() const
Definition Fact.cc:504
Q_INVOKABLE QVariant clamp(const QString &cookedValue)
Convert and clamp value.
Definition Fact.cc:722
QString _variantToString(const QVariant &variant, int decimalPlaces) const
Definition Fact.cc:354
FactValueSliderListModel * _valueSliderModel
Definition Fact.h:210
QVariant cookedDefaultValue() const
Definition Fact.cc:456
QString category() const
Definition Fact.cc:654
bool minIsDefaultForType() const
Definition Fact.cc:624
QVariant _rawValue
Definition Fact.h:204
void _sendValueChangedSignal(const QVariant &value)
Definition Fact.cc:766
void setCookedValue(const QVariant &value)
Definition Fact.cc:157
QVariant rawUserMin() const
Definition Fact.cc:544
void enumsChanged()
QString enumStringValue()
Definition Fact.cc:231
QString label() const
Definition Fact.cc:484
void vehicleUpdated(const QVariant &value)
Signalled when the param write ack comes back from the vehicle.
bool hasControl() const
Definition Fact.cc:818
bool vehicleRebootRequired() const
Definition Fact.cc:738
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
static void adjustSettingMetaData(const QString &settingsGroup, FactMetaData &metaData, bool &userVisible)
bool runningUnitTests()
void showRebootAppMessage(const QString &message, const QString &title)
Modal reboot-required message. Debounced within 2 minutes.