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/QDir>
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QMap>
6#include <QtCore/QObject>
7#include <QtCore/QString>
8#include <QtCore/QTimer>
9#include <QtQmlIntegration/QtQmlIntegration>
10
11#include "Fact.h"
12#include "FactMetaData.h"
13#include "MAVLinkLib.h"
14
15Q_DECLARE_LOGGING_CATEGORY(ParameterManagerLog)
16Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
17Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
18Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
19
21class Vehicle;
22
23class ParameterManager : public QObject
24{
25 Q_OBJECT
26 QML_ELEMENT
27 QML_UNCREATABLE("")
28 Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
30 Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
31 Q_PROPERTY(bool pendingWrites READ pendingWrites NOTIFY pendingWritesChanged)
32 friend class ParameterEditorController;
33
34public:
37
38 bool parametersReady() const { return _parametersReady; }
39 bool missingParameters() const { return _missingParameters; }
40 double loadProgress() const { return _loadProgress; }
41
43 static QDir parameterCacheDir();
44
46 static QString parameterCacheFile(int vehicleId, int componentId);
47
48 void mavlinkMessageReceived(const mavlink_message_t &message);
49
50 QList<int> componentIds() const;
51
53 void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
54
56 void refreshParameter(int componentId, const QString &paramName);
57
59 void refreshParametersPrefix(int componentId, const QString &namePrefix);
60
63
67 bool parameterExists(int componentId, const QString &paramName) const;
68
70 QStringList parameterNames(int componentId) const;
71
76 Fact *getParameter(int componentId, const QString &paramName);
77
79 QString readParametersFromStream(QTextStream &stream);
80
81 void writeParametersToStream(QTextStream &stream) const;
82
83 bool pendingWrites() const;
84
86
87 static MAV_PARAM_TYPE factTypeToMavType(FactMetaData::ValueType_t factType);
88 static FactMetaData::ValueType_t mavTypeToFactType(MAV_PARAM_TYPE mavType);
89
90 static constexpr int defaultComponentId = -1;
91
92 // These are public for creating unit tests
93 static constexpr int kParamSetRetryCount = 2;
94 static constexpr int kParamRequestReadRetryCount = 2;
95 static constexpr int kWaitForParamValueAckMs = 1000;
96 static constexpr int kMaxInitialRequestListRetry = 4;
97 static constexpr int kHashCheckTimeoutMs = 1000;
98 static constexpr int kParamRequestListTimeoutMs = 5000;
99 static constexpr int kTestInitialRequestIntervalMs = 500;
102
103signals:
106 void loadProgressChanged(float value);
108 void factAdded(int componentId, Fact *fact);
109
110 // These signals are used to verify unit tests
111 void _paramSetSuccess(int componentId, const QString &paramName);
112 void _paramSetFailure(int componentId, const QString &paramName);
113 void _paramRequestReadSuccess(int componentId, const QString &paramName, int paramIndex);
114 void _paramRequestReadFailure(int componentId, const QString &paramName, int paramIndex);
115
116private slots:
117 void _factRawValueUpdated(const QVariant &rawValue);
118
119private:
121 void _handleParamValue(int componentId, const QString &parameterName, int parameterCount, int parameterIndex, MAV_PARAM_TYPE mavParamType, const QVariant &parameterValue);
123 void _mavlinkParamSet(int componentId, const QString &name, FactMetaData::ValueType_t valueType, const QVariant &rawValue);
124 void _waitingParamTimeout();
125 void _tryCacheLookup();
126 void _hashCheckTimeout();
127 void _paramRequestListTimeout();
129 int _actualComponentId(int componentId) const;
130 void _mavlinkParamRequestRead(int componentId, const QString &paramName, int paramIndex, bool notifyFailure);
131 void _requestHashCheck(uint8_t componentId);
132 void _writeLocalParamCache(int vehicleId, int componentId);
133 void _tryCacheHashLoad(int vehicleId, int componentId, const QVariant &hashValue);
134 void _loadMetaData();
135 void _clearMetaData();
137 QString _remapParamNameToVersion(const QString &paramName) const;
138 bool _fillMavlinkParamUnion(FactMetaData::ValueType_t valueType, const QVariant &rawValue, mavlink_param_union_t &paramUnion) const;
139 bool _mavlinkParamUnionToVariant(const mavlink_param_union_t &paramUnion, QVariant &outValue) const;
141 void _loadOfflineEditingParams();
142 QString _logVehiclePrefix(int componentId) const;
143 void _setLoadProgress(double loadProgress);
147 bool _fillIndexBatchQueue(bool waitingParamTimeout);
148 void _updateProgressBar();
149 void _checkInitialLoadComplete();
150 void _ftpDownloadComplete(const QString &fileName, const QString &errorMsg);
151 void _ftpDownloadProgress(float progress);
154 bool _parseParamFile(const QString &filename);
155 void _incrementPendingWriteCount();
156 void _decrementPendingWriteCount();
157 QString _vehicleAndComponentString(int componentId) const;
158
159 static QVariant _stringToTypedVariant(const QString &string, FactMetaData::ValueType_t type, bool failOk = false);
160
161 Vehicle *_vehicle = nullptr;
162
163 QMap<int /* comp id */, QMap<QString /* parameter name */, Fact*>> _mapCompId2FactMap;
164
165 double _loadProgress = 0;
166 bool _parametersReady = false;
167 bool _missingParameters = false;
168 bool _initialLoadComplete = false;
169 bool _waitingForDefaultComponent = false;
170 bool _metaDataAddedToFacts = false;
171 bool _logReplay = false;
172 bool _hashCheckDone = false;
173
174 typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
175 typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
176
177 QMap<int /* component id */, bool> _debugCacheCRC;
178 QMap<int /* component id */, CacheMapName2ParamTypeVal> _debugCacheMap;
179 QMap<int /* component id */, QMap<QString /* param name */, bool /* seen */>> _debugCacheParamSeen;
180
181 // Wait counts from previous parameter update cycle
182 int _prevWaitingReadParamIndexCount = 0;
183
184 bool _readParamIndexProgressActive = false;
185
186 static constexpr int _maxInitialRequestListRetry = kMaxInitialRequestListRetry;
187 int _initialRequestRetryCount = 0;
188 static constexpr int _maxInitialLoadRetrySingleParam = 5;
189 bool _disableAllRetries = false;
190
191 bool _indexBatchQueueActive = false;
192 QList<int> _indexBatchQueue;
193
194 QMap<int, int> _paramCountMap;
195 QMap<int, QMap<int, int>> _waitingReadParamIndexMap;
196 QMap<int, QList<int>> _failedReadParamIndexMap;
197
198 int _totalParamCount = 0;
199 int _pendingWritesCount = 0;
200
201 QTimer _hashCheckTimer;
202 QTimer _paramRequestListTimer;
203 QTimer _waitingParamTimeoutTimer;
204
205 Fact _defaultFact;
206
207 bool _tryftp = false;
208};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
A Fact is used to hold a single value within the system.
Definition Fact.h:19
bool parameterExists(int componentId, const QString &paramName) const
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)
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
void refreshAllParameters(uint8_t componentID=MAV_COMP_ID_ALL)
Re-request the full set of parameters from the autopilot.
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 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()
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)