4#include <QtCore/QObject>
5#include <QtCore/QString>
6#include <QtCore/QTimer>
7#include <QtQmlIntegration/QtQmlIntegration>
10#include "MAVLinkEnums.h"
122 void _factRawValueUpdated(
const QVariant &rawValue);
126 void _handleParamValue(
int componentId,
const QString ¶meterName,
int parameterCount,
int parameterIndex, MAV_PARAM_TYPE mavParamType,
const QVariant ¶meterValue);
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 ¶mName,
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 ¶mName)
const;
155 void _loadOfflineEditingParams();
156 QString _logVehiclePrefix(
int componentId)
const;
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;
177 QMap<
int , QMap<QString ,
Fact*>> _mapCompId2FactMap;
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;
190 typedef QPair<
int , QVariant > ParamTypeVal;
191 typedef QMap<QString , ParamTypeVal> CacheMapName2ParamTypeVal;
193 QMap<
int ,
bool> _debugCacheCRC;
194 QMap<
int , CacheMapName2ParamTypeVal> _debugCacheMap;
195 QMap<
int , QMap<QString ,
bool >> _debugCacheParamSeen;
198 int _prevWaitingReadParamIndexCount = 0;
200 bool _readParamIndexProgressActive =
false;
203 int _initialRequestRetryCount = 0;
204 static constexpr int _maxInitialLoadRetrySingleParam = 5;
205 bool _disableAllRetries =
false;
207 bool _indexBatchQueueActive =
false;
208 QList<int> _indexBatchQueue;
210 QMap<int, int> _paramCountMap;
211 QMap<int, QMap<int, int>> _waitingReadParamIndexMap;
212 QMap<int, QList<int>> _failedReadParamIndexMap;
214 int _totalParamCount = 0;
215 int _pendingWritesCount = 0;
217 QTimer _hashCheckTimer;
218 QTimer _paramRequestListTimer;
219 QTimer _waitingParamTimeoutTimer;
223 bool _tryftp =
false;
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.
bool parameterExists(int componentId, const QString ¶mName) 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 ¶mName)
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
void tryHashCheckCacheLoad()
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 resetAllParametersToDefaults()
QStringList parameterNames(int componentId) const
Returns all parameter names.
void _paramRequestReadFailure(int componentId, const QString ¶mName, int paramIndex)
void _paramRequestReadSuccess(int componentId, const QString ¶mName, int paramIndex)
static constexpr int kParamSetRetryCount
Number of retries for PARAM_SET.
void _paramSetSuccess(int componentId, const QString ¶mName)
static constexpr int kMaxInitialRequestListRetry
Maximum retries for initial parameter request list.
void loadProgressChanged(float value)
void cacheCheckOnlyFailed()
void refreshParameter(int componentId, const QString ¶mName)
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 ¶mName)