QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ParameterManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QMap>
4#include <QtCore/QObject>
5#include <QtCore/QString>
6#include <QtCore/QTimer>
7#include <QtQmlIntegration/QtQmlIntegration>
8
9#include "Fact.h"
10#include "MAVLinkEnums.h"
11#include "QGCMAVLinkTypes.h"
12
13class QTextStream;
14
16class Vehicle;
17
18class ParameterManager : public QObject
19{
20 Q_OBJECT
21 QML_ELEMENT
22 QML_UNCREATABLE("")
23 Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
25 Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
26 Q_PROPERTY(bool pendingWrites READ pendingWrites NOTIFY pendingWritesChanged)
29
30public:
33
34 bool parametersReady() const { return _parametersReady; }
35 bool missingParameters() const { return _missingParameters; }
36 double loadProgress() const { return _loadProgress; }
37 bool parameterDownloadSkipped() const { return _parameterDownloadSkipped; }
38 void setParameterDownloadSkipped(bool skipped);
39
41 static QDir parameterCacheDir();
42
44 static QString parameterCacheFile(int vehicleId, int componentId);
45
46 void mavlinkMessageReceived(const mavlink_message_t &message);
47
48 QList<int> componentIds() const;
49
51 void refreshAllParameters(uint8_t componentID);
52 Q_INVOKABLE void refreshAllParameters() { refreshAllParameters(MAV_COMP_ID_ALL); }
53
57
59 void refreshParameter(int componentId, const QString &paramName);
60
62 void refreshParametersPrefix(int componentId, const QString &namePrefix);
63
66
70 bool parameterExists(int componentId, const QString &paramName) const;
71
73 QStringList parameterNames(int componentId) const;
74
79 Fact *getParameter(int componentId, const QString &paramName);
80
82 QString readParametersFromStream(QTextStream &stream);
83
84 void writeParametersToStream(QTextStream &stream) const;
85
86 bool pendingWrites() const;
87
89
90 static MAV_PARAM_TYPE factTypeToMavType(FactMetaData::ValueType_t factType);
91 static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType);
92
93 static constexpr int defaultComponentId = -1;
94
95 // These are public for creating unit tests
96 static constexpr int kParamSetRetryCount = 2;
97 static constexpr int kParamRequestReadRetryCount = 2;
98 static constexpr int kWaitForParamValueAckMs = 1000;
99 static constexpr int kMaxInitialRequestListRetry = 4;
100 static constexpr int kHashCheckTimeoutMs = 1000;
101 static constexpr int kParamRequestListTimeoutMs = 5000;
102 static constexpr int kTestInitialRequestIntervalMs = 500;
105
106signals:
109 void loadProgressChanged(float value);
113 void factAdded(int componentId, Fact *fact);
114
115 // These signals are used to verify unit tests
116 void _paramSetSuccess(int componentId, const QString &paramName);
117 void _paramSetFailure(int componentId, const QString &paramName);
118 void _paramRequestReadSuccess(int componentId, const QString &paramName, int paramIndex);
119 void _paramRequestReadFailure(int componentId, const QString &paramName, int paramIndex);
120
121private slots:
122 void _factRawValueUpdated(const QVariant &rawValue);
123
124private:
126 void _handleParamValue(int componentId, const QString &parameterName, int parameterCount, int parameterIndex, MAV_PARAM_TYPE mavParamType, const QVariant &parameterValue);
128 void _mavlinkParamSet(int componentId, const QString &name, FactMetaData::ValueType_t valueType, const QVariant &rawValue);
129 void _waitingParamTimeout();
130 void _tryCacheLookup();
131 void _resetHashCheck();
132 void _startParameterDownload(uint8_t componentId);
133 void _hashCheckTimeout();
134 void _paramRequestListTimeout();
136 int _actualComponentId(int componentId) const;
137 void _mavlinkParamRequestRead(int componentId, const QString &paramName, int paramIndex, bool notifyFailure);
138 void _requestHashCheck(uint8_t componentId);
139 void _writeLocalParamCache(int vehicleId, int componentId);
140 void _tryCacheHashLoad(int vehicleId, int componentId, const QVariant &hashValue);
141 void _loadMetaData();
142 void _clearMetaData();
151 QString _remapParamNameToVersion(const QString &paramName) const;
152 bool _fillMavlinkParamUnion(FactMetaData::ValueType_t valueType, const QVariant &rawValue, mavlink_param_union_t &paramUnion) const;
153 bool _mavlinkParamUnionToVariant(const mavlink_param_union_t &paramUnion, QVariant &outValue) const;
155 void _loadOfflineEditingParams();
156 QString _logVehiclePrefix(int componentId) const;
157 void _setLoadProgress(double loadProgress);
161 bool _fillIndexBatchQueue(bool waitingParamTimeout);
162 void _updateProgressBar();
163 void _checkInitialLoadComplete();
164 void _ftpDownloadComplete(const QString &fileName, const QString &errorMsg);
165 void _ftpDownloadProgress(float progress);
168 bool _parseParamFile(const QString &filename);
169 void _incrementPendingWriteCount();
170 void _decrementPendingWriteCount();
171 QString _vehicleAndComponentString(int componentId) const;
172
173 static QVariant _stringToTypedVariant(const QString &string, FactMetaData::ValueType_t type, bool failOk = false);
174
175 Vehicle *_vehicle = nullptr;
176
177 QMap<int /* comp id */, QMap<QString /* parameter name */, Fact*>> _mapCompId2FactMap;
178
179 double _loadProgress = 0;
180 bool _parametersReady = false;
181 bool _parameterDownloadSkipped = false;
182 bool _missingParameters = false;
183 bool _initialLoadComplete = false;
184 bool _waitingForDefaultComponent = false;
185 bool _metaDataAddedToFacts = false;
186 bool _logReplay = false;
187 bool _hashCheckDone = false;
188 bool _cacheOnlyHashCheck = false;
189
190 typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
191 typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
192
193 QMap<int /* component id */, bool> _debugCacheCRC;
194 QMap<int /* component id */, CacheMapName2ParamTypeVal> _debugCacheMap;
195 QMap<int /* component id */, QMap<QString /* param name */, bool /* seen */>> _debugCacheParamSeen;
196
197 // Wait counts from previous parameter update cycle
198 int _prevWaitingReadParamIndexCount = 0;
199
200 bool _readParamIndexProgressActive = false;
201
202 static constexpr int _maxInitialRequestListRetry = kMaxInitialRequestListRetry;
203 int _initialRequestRetryCount = 0;
204 static constexpr int _maxInitialLoadRetrySingleParam = 5;
205 bool _disableAllRetries = false;
206
207 bool _indexBatchQueueActive = false;
208 QList<int> _indexBatchQueue;
209
210 QMap<int, int> _paramCountMap;
211 QMap<int, QMap<int, int>> _waitingReadParamIndexMap;
212 QMap<int, QList<int>> _failedReadParamIndexMap;
213
214 int _totalParamCount = 0;
215 int _pendingWritesCount = 0;
216
217 QTimer _hashCheckTimer;
218 QTimer _paramRequestListTimer;
219 QTimer _waitingParamTimeoutTimer;
220
221 Fact _defaultFact;
222
223 bool _tryftp = false;
224};
struct __mavlink_message mavlink_message_t
struct param_union mavlink_param_union_t
A Fact is used to hold a single value within the system.
Definition Fact.h:17
bool parameterExists(int componentId, const QString &paramName) const
void parameterDownloadSkippedChanged()
static constexpr int kWaitForParamValueAckMs
Time to wait for param value ack after set param.
void mavlinkMessageReceived(const mavlink_message_t &message)
static constexpr int kParamRequestListTimeoutMs
Timeout for PARAM_REQUEST_LIST response.
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int kTestInitialRequestIntervalMs
void factAdded(int componentId, Fact *fact)
static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType)
void setParameterDownloadSkipped(bool skipped)
QList< int > componentIds() const
void refreshParametersPrefix(int componentId, const QString &namePrefix)
Request a refresh on all parameters that begin with the specified prefix.
void parametersReadyChanged(bool parametersReady)
QString readParametersFromStream(QTextStream &stream)
Returns error messages from loading.
double loadProgress() const
bool pendingWrites() const
static QDir parameterCacheDir()
static constexpr int kHashCheckTimeoutMs
Timeout for standalone _HASH_CHECK request.
void missingParametersChanged(bool missingParameters)
bool parametersReady() const
static constexpr int defaultComponentId
QStringList parameterNames(int componentId) const
Returns all parameter names.
void _paramRequestReadFailure(int componentId, const QString &paramName, int paramIndex)
void _paramRequestReadSuccess(int componentId, const QString &paramName, int paramIndex)
static constexpr int kParamSetRetryCount
Number of retries for PARAM_SET.
void _paramSetSuccess(int componentId, const QString &paramName)
static constexpr int kMaxInitialRequestListRetry
Maximum retries for initial parameter request list.
void loadProgressChanged(float value)
void cacheCheckOnlyFailed()
void refreshParameter(int componentId, const QString &paramName)
Request a refresh on the specific parameter.
void pendingWritesChanged(bool pendingWrites)
static MAV_PARAM_TYPE factTypeToMavType(FactMetaData::ValueType_t factType)
static constexpr int kParamRequestReadRetryCount
Number of retries for PARAM_REQUEST_READ.
bool missingParameters() const
void resetAllToVehicleConfiguration()
bool parameterDownloadSkipped() const
Q_INVOKABLE void refreshAllParameters()
static QString parameterCacheFile(int vehicleId, int componentId)
void writeParametersToStream(QTextStream &stream) const
static constexpr int kTestMaxInitialRequestTimeMs
Maximum time to wait for initial request retries to exhaust in tests.
void _paramSetFailure(int componentId, const QString &paramName)