QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FactGroup.cc
Go to the documentation of this file.
1#include "FactGroup.h"
2
3#include <QtCore/QJsonArray>
4
6
7QGC_LOGGING_CATEGORY(FactGroupLog, "FactSystem.FactGroup")
8
9FactGroup::FactGroup(int updateRateMsecs, const QString &metaDataFile, QObject *parent, bool ignoreCamelCase)
10 : QObject(parent)
11 , _updateRateMSecs(updateRateMsecs)
12 , _ignoreCamelCase(ignoreCamelCase)
13{
14 // qCDebug(FactGroupLog) << Q_FUNC_INFO << this;
15 _setupTimer();
16 _nameToFactMetaDataMap = FactMetaData::createMapFromJsonFile(metaDataFile, this);
17}
18
19FactGroup::FactGroup(int updateRateMsecs, QObject *parent, bool ignoreCamelCase)
20 : QObject(parent)
21 , _updateRateMSecs(updateRateMsecs)
22 , _ignoreCamelCase(ignoreCamelCase)
23{
24 // qCDebug(FactGroupLog) << Q_FUNC_INFO << this;
25 _setupTimer();
26}
27
29{
30 // qCDebug(FactGroupLog) << Q_FUNC_INFO << this;
31}
32
33void FactGroup::_loadFromJsonArray(const QJsonArray &jsonArray)
34{
35 QMap<QString, QString> defineMap;
37}
38
39void FactGroup::_setupTimer()
40{
41 if (_updateRateMSecs > 0) {
42 (void) connect(&_updateTimer, &QTimer::timeout, this, &FactGroup::_updateAllValues);
43 _updateTimer.setSingleShot(false);
44 _updateTimer.setInterval(_updateRateMSecs);
45 _updateTimer.start();
46 }
47}
48
49bool FactGroup::factExists(const QString &name) const
50{
51 if (name.contains(".")) {
52 const QStringList parts = name.split(".");
53 if (parts.count() != 2) {
54 qCWarning(FactGroupLog) << "Only single level of hierarchy supported";
55 return false;
56 }
57
58 FactGroup *const factGroup = getFactGroup(parts[0]);
59 if (!factGroup) {
60 qCWarning(FactGroupLog) << "Unknown FactGroup" << parts[0];
61 return false;
62 }
63
64 return factGroup->factExists(parts[1]);
65 }
66
67 const QString camelCaseName = _ignoreCamelCase ? name : _camelCase(name);
68
69 return _nameToFactMap.contains(camelCaseName);
70}
71
72Fact *FactGroup::getFact(const QString &name) const
73{
74 if (name.contains(".")) {
75 const QStringList parts = name.split(".");
76 if (parts.count() != 2) {
77 qCWarning(FactGroupLog) << "Only single level of hierarchy supported";
78 return nullptr;
79 }
80
81 FactGroup *const factGroup = getFactGroup(parts[0]);
82 if (!factGroup) {
83 qCWarning(FactGroupLog) << "Unknown FactGroup" << parts[0];
84 return nullptr;
85 }
86
87 return factGroup->getFact(parts[1]);
88 }
89
90 Fact *fact = nullptr;
91 const QString camelCaseName = _ignoreCamelCase ? name : _camelCase(name);
92
93 if (_nameToFactMap.contains(camelCaseName)) {
94 fact = _nameToFactMap[camelCaseName];
95 } else {
96 qCWarning(FactGroupLog) << "Unknown Fact" << camelCaseName;
97 }
98
99 return fact;
100}
101
102FactGroup *FactGroup::getFactGroup(const QString &name) const
103{
104 FactGroup * factGroup = nullptr;
105 const QString camelCaseName = _ignoreCamelCase ? name : _camelCase(name);
106
107 if (_nameToFactGroupMap.contains(camelCaseName)) {
108 factGroup = _nameToFactGroupMap[camelCaseName];
109 } else {
110 qCWarning(FactGroupLog) << "Unknown FactGroup" << camelCaseName;
111 }
112
113 return factGroup;
114}
115
116void FactGroup::_addFact(Fact *fact, const QString &name)
117{
118 if (_nameToFactMap.contains(name)) {
119 qCWarning(FactGroupLog) << "Duplicate Fact" << name;
120 return;
121 }
122
124 if (_nameToFactMetaDataMap.contains(name)) {
125 fact->setMetaData(_nameToFactMetaDataMap[name], true /* setDefaultFromMetaData */);
126 }
127 _nameToFactMap[name] = fact;
128 _factNames.append(name);
129
130 emit factNamesChanged();
131}
132
133void FactGroup::_addFactGroup(FactGroup *factGroup, const QString &name)
134{
135 if (_nameToFactGroupMap.contains(name)) {
136 qCWarning(FactGroupLog) << "Duplicate FactGroup" << name;
137 return;
138 }
139
140 _nameToFactGroupMap[name] = factGroup;
141
143}
144
146{
147 for (Fact *fact: _nameToFactMap) {
148 fact->sendDeferredValueChangedSignal();
149 }
150}
151
152void FactGroup::setLiveUpdates(bool liveUpdates)
153{
154 if (_updateTimer.interval() == 0) {
155 return;
156 }
157
158 if (liveUpdates) {
159 _updateTimer.stop();
160 } else {
161 _updateTimer.start();
162 }
163
164 for (Fact *fact: _nameToFactMap) {
165 fact->setSendValueChangedSignals(liveUpdates);
166 }
167}
168
169
170QString FactGroup::_camelCase(const QString &text)
171{
172 return (text[0].toLower() + text.right(text.length() - 1));
173}
174
175void FactGroup::_setTelemetryAvailable (bool telemetryAvailable)
176{
177 if (telemetryAvailable != _telemetryAvailable) {
178 _telemetryAvailable = telemetryAvailable;
179 emit telemetryAvailableChanged(_telemetryAvailable);
180 }
181}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
QMap< QString, Fact * > _nameToFactMap
Definition FactGroup.h:69
void telemetryAvailableChanged(bool telemetryAvailable)
QMap< QString, FactMetaData * > _nameToFactMetaDataMap
Definition FactGroup.h:71
virtual void _updateAllValues()
Definition FactGroup.cc:145
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:175
Q_INVOKABLE Fact * getFact(const QString &name) const
Definition FactGroup.cc:72
void factGroupNamesChanged()
FactGroup(int updateRateMsecs, const QString &metaDataFile, QObject *parent=nullptr, bool ignoreCamelCase=false)
< false: No telemetry for these values has been received
Definition FactGroup.cc:9
void _addFactGroup(FactGroup *factGroup, const QString &name)
Definition FactGroup.cc:133
Q_INVOKABLE bool factExists(const QString &name) const
@ return true: if the fact exists in the group
Definition FactGroup.cc:49
void factNamesChanged()
QMap< QString, FactGroup * > _nameToFactGroupMap
Definition FactGroup.h:70
QStringList _factNames
Definition FactGroup.h:72
void _addFact(Fact *fact, const QString &name)
Definition FactGroup.cc:116
Q_INVOKABLE FactGroup * getFactGroup(const QString &name) const
Definition FactGroup.cc:102
Q_INVOKABLE void setLiveUpdates(bool liveUpdates)
Turning on live updates will allow value changes to flow through as they are received.
Definition FactGroup.cc:152
virtual ~FactGroup()
Definition FactGroup.cc:28
bool telemetryAvailable() const
Definition FactGroup.h:45
const int _updateRateMSecs
Update rate for Fact::valueChanged signals, 0: immediate update.
Definition FactGroup.h:67
void _loadFromJsonArray(const QJsonArray &jsonArray)
Definition FactGroup.cc:33
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
static QMap< QString, FactMetaData * > createMapFromJsonArray(const QJsonArray &jsonArray, const DefineMap_t &defineMap, QObject *metaDataParent)
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
Definition Fact.cc:674
void setSendValueChangedSignals(bool sendValueChangedSignals)
Definition Fact.cc:758