4#include <QtCore/QLoggingCategory>
6#include <QtCore/QObject>
7#include <QtCore/QString>
8#include <QtCore/QTimer>
9#include <QtQmlIntegration/QtQmlIntegration>
117 void _factRawValueUpdated(
const QVariant &rawValue);
121 void _handleParamValue(
int componentId,
const QString ¶meterName,
int parameterCount,
int parameterIndex, MAV_PARAM_TYPE mavParamType,
const QVariant ¶meterValue);
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 ¶mName,
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 ¶mName)
const;
138 bool _fillMavlinkParamUnion(
FactMetaData::ValueType_t valueType,
const QVariant &rawValue, mavlink_param_union_t ¶mUnion)
const;
139 bool _mavlinkParamUnionToVariant(
const mavlink_param_union_t ¶mUnion, QVariant &outValue)
const;
141 void _loadOfflineEditingParams();
142 QString _logVehiclePrefix(
int componentId)
const;
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;
163 QMap<
int , QMap<QString ,
Fact*>> _mapCompId2FactMap;
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;
174 typedef QPair<
int , QVariant > ParamTypeVal;
175 typedef QMap<QString , ParamTypeVal> CacheMapName2ParamTypeVal;
177 QMap<
int ,
bool> _debugCacheCRC;
178 QMap<
int , CacheMapName2ParamTypeVal> _debugCacheMap;
179 QMap<
int , QMap<QString ,
bool >> _debugCacheParamSeen;
182 int _prevWaitingReadParamIndexCount = 0;
184 bool _readParamIndexProgressActive =
false;
187 int _initialRequestRetryCount = 0;
188 static constexpr int _maxInitialLoadRetrySingleParam = 5;
189 bool _disableAllRetries =
false;
191 bool _indexBatchQueueActive =
false;
192 QList<int> _indexBatchQueue;
194 QMap<int, int> _paramCountMap;
195 QMap<int, QMap<int, int>> _waitingReadParamIndexMap;
196 QMap<int, QList<int>> _failedReadParamIndexMap;
198 int _totalParamCount = 0;
199 int _pendingWritesCount = 0;
201 QTimer _hashCheckTimer;
202 QTimer _paramRequestListTimer;
203 QTimer _waitingParamTimeoutTimer;
207 bool _tryftp =
false;
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
A Fact is used to hold a single value within the system.
bool parameterExists(int componentId, const QString ¶mName) 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 ¶mName)
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 resetAllParametersToDefaults()
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 ¶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 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()
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)