QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ParameterManager.cc
Go to the documentation of this file.
1#include "ParameterManager.h"
2#include "AutoPilotPlugin.h"
3#include "CompInfoParam.h"
5#include "FactGroup.h"
6#include "FirmwarePlugin.h"
7#include "FTPManager.h"
8#include "MAVLinkProtocol.h"
9#include "QGC.h"
10#include "QGCApplication.h"
11#include "QGCLoggingCategory.h"
12#include "Vehicle.h"
13#include "QGCStateMachine.h"
14#include "MultiVehicleManager.h"
15
16#include <QtCore/QEasingCurve>
17#include <QtCore/QFile>
18#include <QtCore/QStandardPaths>
19#include <QtCore/QVariantAnimation>
20
21QGC_LOGGING_CATEGORY(ParameterManagerLog, "FactSystem.ParameterManager")
22QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "FactSystem.ParameterManager:verbose1")
23QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "FactSystem.ParameterManager:verbose2")
24QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog, "FactSystem.ParameterManager:debugCacheFailure") // Turn on to debug parameter cache crc misses
25
27 : QObject(vehicle)
28 , _vehicle(vehicle)
29 , _logReplay(!vehicle->vehicleLinkManager()->primaryLink().expired() && vehicle->vehicleLinkManager()->primaryLink().lock()->isLogReplay())
30 , _disableAllRetries(_logReplay)
31 , _tryftp(vehicle->apmFirmware())
32{
33 qCDebug(ParameterManagerLog) << this;
34
35 if (_vehicle->isOfflineEditingVehicle()) {
36 _loadOfflineEditingParams();
37 return;
38 }
39
40 if (_logReplay) {
41 qCDebug(ParameterManagerLog) << this << "In log replay mode";
42 }
43
44 _hashCheckTimer.setSingleShot(true);
45 _hashCheckTimer.setInterval(kHashCheckTimeoutMs);
46 (void) connect(&_hashCheckTimer, &QTimer::timeout, this, &ParameterManager::_hashCheckTimeout);
47
48 _paramRequestListTimer.setSingleShot(true);
49 _paramRequestListTimer.setInterval(qgcApp()->runningUnitTests() ? kTestInitialRequestIntervalMs : kParamRequestListTimeoutMs);
50 (void) connect(&_paramRequestListTimer, &QTimer::timeout, this, &ParameterManager::_paramRequestListTimeout);
51
52 _waitingParamTimeoutTimer.setSingleShot(true);
53 _waitingParamTimeoutTimer.setInterval(qgcApp()->runningUnitTests() ? 500 : 3000);
54 if (!_logReplay) {
55 (void) connect(&_waitingParamTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_waitingParamTimeout);
56 }
57
58 // Ensure the cache directory exists
59 (void) QDir().mkpath(parameterCacheDir().absolutePath());
60}
61
63{
64 qCDebug(ParameterManagerLog) << this;
65}
66
67void ParameterManager::_updateProgressBar()
68{
69 int waitingReadParamIndexCount = 0;
70
71 for (const int compId: _waitingReadParamIndexMap.keys()) {
72 waitingReadParamIndexCount += _waitingReadParamIndexMap[compId].count();
73 }
74
75 if (waitingReadParamIndexCount == 0) {
76 if (_readParamIndexProgressActive) {
77 _readParamIndexProgressActive = false;
78 _setLoadProgress(0.0);
79 return;
80 }
81 } else {
82 _readParamIndexProgressActive = true;
83 _setLoadProgress(static_cast<double>(_totalParamCount - waitingReadParamIndexCount) / static_cast<double>(_totalParamCount));
84 return;
85 }
86}
87
89{
90 if (_tryftp && (message.compid == MAV_COMP_ID_AUTOPILOT1) && !_initialLoadComplete)
91 return;
92
93 if (message.msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
94 mavlink_param_value_t param_value{};
95 mavlink_msg_param_value_decode(&message, &param_value);
96
97 // This will null terminate the name string
98 char parameterNameWithNull[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1] = {};
99 (void) strncpy(parameterNameWithNull, param_value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
100 const QString parameterName(parameterNameWithNull);
101
102 mavlink_param_union_t paramUnion{};
103 paramUnion.param_float = param_value.param_value;
104 paramUnion.type = param_value.param_type;
105
106 QVariant parameterValue;
107 if (!_mavlinkParamUnionToVariant(paramUnion, parameterValue)) {
108 return;
109 }
110
111 _handleParamValue(message.compid, parameterName, param_value.param_count, param_value.param_index, static_cast<MAV_PARAM_TYPE>(param_value.param_type), parameterValue);
112 }
113}
114
115void ParameterManager::_handleParamValue(int componentId, const QString &parameterName, int parameterCount, int parameterIndex, MAV_PARAM_TYPE mavParamType, const QVariant &parameterValue)
116{
117
118 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
119 "_parameterUpdate" <<
120 "name:" << parameterName <<
121 "count:" << parameterCount <<
122 "index:" << parameterIndex <<
123 "mavType:" << mavParamType <<
124 "value:" << parameterValue <<
125 ")";
126
127 // ArduPilot has this strange behavior of streaming parameters that we didn't ask for. This even happens before it responds to the
128 // PARAM_REQUEST_LIST. We disregard any of this until the initial request is responded to.
129 if ((parameterIndex == 65535) && (parameterName != QStringLiteral("_HASH_CHECK")) && _paramRequestListTimer.isActive()) {
130 qCDebug(ParameterManagerLog) << "Disregarding unrequested param prior to initial list response" << parameterName;
131 return;
132 }
133
134 if (_vehicle->px4Firmware() && (parameterName == "_HASH_CHECK")) {
135 _hashCheckTimer.stop();
136 if (!_initialLoadComplete && !_logReplay) {
137 /* we received a cache hash, potentially load from cache */
138 _tryCacheHashLoad(_vehicle->id(), componentId, parameterValue);
139 }
140 return;
141 }
142
143 _paramRequestListTimer.stop();
144
145 // Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
146 if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
147 if (_debugCacheMap[componentId].contains(parameterName)) {
148 const ParamTypeVal &cacheParamTypeVal = _debugCacheMap[componentId][parameterName];
149 const size_t dataSize = FactMetaData::typeToSize(static_cast<FactMetaData::ValueType_t>(cacheParamTypeVal.first));
150 const void *const cacheData = cacheParamTypeVal.second.constData();
151 const void *const vehicleData = parameterValue.constData();
152
153 if (memcmp(cacheData, vehicleData, dataSize) != 0) {
154 qCDebug(ParameterManagerVerbose1Log) << "Cache/Vehicle values differ for name:cache:actual" << parameterName << parameterValue << cacheParamTypeVal.second;
155 }
156 _debugCacheParamSeen[componentId][parameterName] = true;
157 } else {
158 qCDebug(ParameterManagerVerbose1Log) << "Parameter missing from cache" << parameterName;
159 }
160 }
161
162 _waitingParamTimeoutTimer.stop();
163
164 // Update our total parameter counts
165 if (!_paramCountMap.contains(componentId)) {
166 _paramCountMap[componentId] = parameterCount;
167 _totalParamCount += parameterCount;
168 }
169
170 // If we've never seen this component id before, setup the index wait lists.
171 if (!_waitingReadParamIndexMap.contains(componentId)) {
172 // Add all indices to the wait list, parameter index is 0-based
173 for (int waitingIndex = 0; waitingIndex < parameterCount; waitingIndex++) {
174 // This will add the new component id, as well as the the new waiting index and set the retry count for that index to 0
175 _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
176 }
177
178 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Seeing component for first time - paramcount:" << parameterCount;
179 }
180
181 if (!_waitingReadParamIndexMap[componentId].contains(parameterIndex)) {
182 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName;
183 }
184
185 // Remove this parameter from the waiting lists
186 if (_waitingReadParamIndexMap[componentId].contains(parameterIndex)) {
187 _waitingReadParamIndexMap[componentId].remove(parameterIndex);
188 (void) _indexBatchQueue.removeOne(parameterIndex);
189 _fillIndexBatchQueue(false /* waitingParamTimeout */);
190 }
191
192 // Track how many parameters we are still waiting for
193 int waitingReadParamIndexCount = 0;
194
195 for (const int waitingComponentId: _waitingReadParamIndexMap.keys()) {
196 waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
197 }
198 if (waitingReadParamIndexCount) {
199 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "waitingReadParamIndexCount:" << waitingReadParamIndexCount;
200 }
201
202 const int readWaitingParamCount = waitingReadParamIndexCount;
203 const int totalWaitingParamCount = readWaitingParamCount;
204 if (totalWaitingParamCount) {
205 // More params to wait for, restart timer
206 _waitingParamTimeoutTimer.start();
207 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
208 } else if (!_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
209 // Still waiting for parameters from default component
210 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
211 _waitingParamTimeoutTimer.start();
212 } else {
213 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
214 }
215
216 _updateProgressBar();
217
218 Fact *fact = nullptr;
219 if (_mapCompId2FactMap.contains(componentId) && _mapCompId2FactMap[componentId].contains(parameterName)) {
220 fact = _mapCompId2FactMap[componentId][parameterName];
221 } else {
222 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
223
224 fact = new Fact(componentId, parameterName, mavTypeToFactType(mavParamType), this);
225 FactMetaData *const factMetaData = _vehicle->compInfoManager()->compInfoParam(componentId)->factMetaDataForName(parameterName, fact->type());
226 fact->setMetaData(factMetaData);
227
228 _mapCompId2FactMap[componentId][parameterName] = fact;
229
230 // We need to know when the fact value changes so we can update the vehicle
231 (void) connect(fact, &Fact::containerRawValueChanged, this, &ParameterManager::_factRawValueUpdated);
232
233 emit factAdded(componentId, fact);
234 }
235
236 fact->containerSetRawValue(parameterValue);
237
238 // Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
239 // which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
240 // which in turn causes a perf problem with all the param cache updates.
241 if (!_logReplay && _vehicle->px4Firmware()) {
242 if (_prevWaitingReadParamIndexCount != 0 && readWaitingParamCount == 0) {
243 // All reads just finished, update the cache
244 _writeLocalParamCache(_vehicle->id(), componentId);
245 }
246 }
247
248 _prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
249
250 _checkInitialLoadComplete();
251
252 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_parameterUpdate complete";
253}
254
255QString ParameterManager::_vehicleAndComponentString(int componentId) const
256{
257 // If there are multiple vehicles include the vehicle id for disambiguation
258 QString vehicleIdStr;
259 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
260 vehicleIdStr = QStringLiteral("veh: %1").arg(_vehicle->id());
261 }
262
263 // IF we have parameters for multiple components include the component id for disambiguation
264 QString componentIdStr;
265 if (_mapCompId2FactMap.keys().count() > 1) {
266 componentIdStr = QStringLiteral("comp: %1").arg(componentId);
267 }
268
269 if (!vehicleIdStr.isEmpty() && !componentIdStr.isEmpty()) {
270 return vehicleIdStr + QStringLiteral(" ") + componentIdStr;
271 } else if (!vehicleIdStr.isEmpty()) {
272 return vehicleIdStr;
273 } else if (!componentIdStr.isEmpty()) {
274 return componentIdStr;
275 } else {
276 return QString();
277 }
278}
279
280void ParameterManager::_mavlinkParamSet(int componentId, const QString &paramName, FactMetaData::ValueType_t valueType, const QVariant &rawValue)
281{
282 auto paramSetEncoder = [this, componentId, paramName, valueType, rawValue](uint8_t /*systemId*/, uint8_t channel, mavlink_message_t *message) -> void {
283 const MAV_PARAM_TYPE paramType = factTypeToMavType(valueType);
284
285 mavlink_param_union_t union_value{};
286 if (!_fillMavlinkParamUnion(valueType, rawValue, union_value)) {
287 return;
288 }
289
290 char paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1] = {};
291 (void) strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
292
293 (void) mavlink_msg_param_set_pack_chan(
296 channel,
297 message,
298 static_cast<uint8_t>(_vehicle->id()),
299 static_cast<uint8_t>(componentId),
300 paramId,
301 union_value.param_float,
302 static_cast<uint8_t>(paramType));
303 };
304
305 auto checkForCorrectParamValue = [this, componentId, paramName, rawValue](const mavlink_message_t &message) -> bool {
306 if (message.compid != componentId) {
307 return false;
308 }
309
310 mavlink_param_value_t param_value{};
311 mavlink_msg_param_value_decode(&message, &param_value);
312
313 // This will null terminate the name string
314 char parameterNameWithNull[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1] = {};
315 (void) strncpy(parameterNameWithNull, param_value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
316 const QString parameterName(parameterNameWithNull);
317
318 if (parameterName != paramName) {
319 return false;
320 }
321
322 // Check that the value matches what we expect within tolerance, if it doesn't match then this message is not for us
323 QVariant receivedValue;
324 mavlink_param_union_t param_union;
325 param_union.param_float = param_value.param_value;
326 param_union.type = param_value.param_type;
327 if (!_mavlinkParamUnionToVariant(param_union, receivedValue)) {
328 return false;
329 }
330 if (rawValue.typeId() != receivedValue.typeId()) {
331 qCWarning(ParameterManagerLog) << "QVariant type mismatch on PARAM_VALUE ack for" << paramName << ": expected type" << rawValue.typeId() << "got type" << receivedValue.typeId();
332 return false;
333 }
334 if (param_value.param_type == MAV_PARAM_TYPE_REAL32) {
335 // Float comparison must be fuzzy
336 return QGC::fuzzyCompare(rawValue.toFloat(), receivedValue.toFloat());
337 } else {
338 return receivedValue == rawValue;
339 }
340 };
341
342 // State Machine:
343 // Send PARAM_SET - 2 retries after initial attempt
344 // Increment pending write count
345 // Wait for PARAM_VALUE ack
346 // Decrement pending write count
347 //
348 // timeout:
349 // Decrement pending write count
350 // Back up to PARAM_SET for retries
351 //
352 // error:
353 // Refresh parameter from vehicle
354 // Notify user of failure
355
356 // Create states
357 auto stateMachine = new QGCStateMachine(QStringLiteral("ParameterManager PARAM_SET"), vehicle(), this);
358 auto sendParamSetState = new SendMavlinkMessageState(stateMachine, paramSetEncoder, kParamSetRetryCount);
359 auto incPendingWriteCountState = new FunctionState(QStringLiteral("ParameterManager increment pending write count"), stateMachine, [this]() {
360 _incrementPendingWriteCount();
361 });
362 auto decPendingWriteCountState = new FunctionState(QStringLiteral("ParameterManager decrement pending write count"), stateMachine, [this]() {
363 _decrementPendingWriteCount();
364 });
365 auto retryDecPendingWriteCountState = new FunctionState(QStringLiteral("ParameterManager retry decrement pending write count"), stateMachine, [this]() {
366 _decrementPendingWriteCount();
367 });
368 auto waitAckState = new WaitForMavlinkMessageState(stateMachine, MAVLINK_MSG_ID_PARAM_VALUE, kWaitForParamValueAckMs, checkForCorrectParamValue);
369 auto paramRefreshState = new FunctionState(QStringLiteral("ParameterManager param refresh"), stateMachine, [this, componentId, paramName]() {
370 refreshParameter(componentId, paramName);
371 });
372 auto userNotifyState = new ShowAppMessageState(stateMachine, QStringLiteral("Parameter write failed: param: %1 %2").arg(paramName).arg(_vehicleAndComponentString(componentId)));
373 auto logSuccessState = new FunctionState(QStringLiteral("ParameterManager log success"), stateMachine, [this, componentId, paramName]() {
374 qCDebug(ParameterManagerLog) << "Parameter write succeeded: param:" << paramName << _vehicleAndComponentString(componentId);
375 emit _paramSetSuccess(componentId, paramName);
376 });
377 auto logFailureState = new FunctionState(QStringLiteral("ParameterManager log failure"), stateMachine, [this, componentId, paramName]() {
378 qCDebug(ParameterManagerLog) << "Parameter write failed: param:" << paramName << _vehicleAndComponentString(componentId);
379 emit _paramSetFailure(componentId, paramName);
380 });
381 auto finalState = new QGCFinalState(stateMachine);
382
383 // Successful state machine transitions
384 stateMachine->setInitialState(sendParamSetState);
385 sendParamSetState->addThisTransition (&QGCState::advance, incPendingWriteCountState);
386 incPendingWriteCountState->addThisTransition(&QGCState::advance, waitAckState);
387 waitAckState->addThisTransition (&QGCState::advance, decPendingWriteCountState);
388 decPendingWriteCountState->addThisTransition(&QGCState::advance, logSuccessState);
389 logSuccessState->addThisTransition (&QGCState::advance, finalState);
390
391 // Retry transitions
392 waitAckState->addTransition(waitAckState, &WaitForMavlinkMessageState::timeout, retryDecPendingWriteCountState); // Retry on timeout
393 retryDecPendingWriteCountState->addThisTransition(&QGCState::advance, sendParamSetState);
394
395 // Error transitions
396 sendParamSetState->addThisTransition(&QGCState::error, logFailureState); // Error is signaled after retries exhausted or internal error
397
398 // Error state branching transitions
399 logFailureState->addThisTransition (&QGCState::advance, userNotifyState);
400 userNotifyState->addThisTransition (&QGCState::advance, paramRefreshState);
401 paramRefreshState->addThisTransition(&QGCState::advance, finalState);
402
403 qCDebug(ParameterManagerLog) << "Starting state machine for PARAM_SET on: " << paramName << _vehicleAndComponentString(componentId);
404 stateMachine->start();
405}
406
407bool ParameterManager::_fillMavlinkParamUnion(FactMetaData::ValueType_t valueType, const QVariant &rawValue, mavlink_param_union_t &paramUnion) const
408{
409 bool ok = false;
410
411 switch (valueType) {
413 paramUnion.param_uint8 = static_cast<uint8_t>(rawValue.toUInt(&ok));
414 break;
416 paramUnion.param_int8 = static_cast<int8_t>(rawValue.toInt(&ok));
417 break;
419 paramUnion.param_uint16 = static_cast<uint16_t>(rawValue.toUInt(&ok));
420 break;
422 paramUnion.param_int16 = static_cast<int16_t>(rawValue.toInt(&ok));
423 break;
425 paramUnion.param_uint32 = static_cast<uint32_t>(rawValue.toUInt(&ok));
426 break;
428 paramUnion.param_float = rawValue.toFloat(&ok);
429 break;
431 paramUnion.param_int32 = static_cast<int32_t>(rawValue.toInt(&ok));
432 break;
433 default:
434 qCCritical(ParameterManagerLog) << "Internal Error: Unsupported fact value type" << valueType;
435 paramUnion.param_int32 = static_cast<int32_t>(rawValue.toInt(&ok));
436 break;
437 }
438
439 if (!ok) {
440 qCCritical(ParameterManagerLog) << "Fact Failed to Convert to Param Type:" << valueType;
441 return false;
442 }
443
444 return true;
445}
446
447bool ParameterManager::_mavlinkParamUnionToVariant(const mavlink_param_union_t &paramUnion, QVariant &outValue) const
448{
449 switch (paramUnion.type) {
450 case MAV_PARAM_TYPE_REAL32:
451 outValue = QVariant(paramUnion.param_float);
452 return true;
453 case MAV_PARAM_TYPE_UINT8:
454 outValue = QVariant(paramUnion.param_uint8);
455 return true;
456 case MAV_PARAM_TYPE_INT8:
457 outValue = QVariant(paramUnion.param_int8);
458 return true;
459 case MAV_PARAM_TYPE_UINT16:
460 outValue = QVariant(paramUnion.param_uint16);
461 return true;
462 case MAV_PARAM_TYPE_INT16:
463 outValue = QVariant(paramUnion.param_int16);
464 return true;
465 case MAV_PARAM_TYPE_UINT32:
466 outValue = QVariant(paramUnion.param_uint32);
467 return true;
468 case MAV_PARAM_TYPE_INT32:
469 outValue = QVariant(paramUnion.param_int32);
470 return true;
471 default:
472 qCCritical(ParameterManagerLog) << "ParameterManager::_mavlinkParamUnionToVariant - unsupported MAV_PARAM_TYPE" << paramUnion.type;
473 return false;
474 }
475}
476
477void ParameterManager::_factRawValueUpdated(const QVariant &rawValue)
478{
479 Fact *const fact = qobject_cast<Fact*>(sender());
480 if (!fact) {
481 qCWarning(ParameterManagerLog) << "Internal error";
482 return;
483 }
484
485 _mavlinkParamSet(fact->componentId(), fact->name(), fact->type(), rawValue);
486}
487
488void ParameterManager::_ftpDownloadComplete(const QString &fileName, const QString &errorMsg)
489{
490 bool continueWithDefaultParameterdownload = true;
491 bool immediateRetry = false;
492
493 (void) disconnect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &ParameterManager::_ftpDownloadComplete);
494 (void) disconnect(_vehicle->ftpManager(), &FTPManager::commandProgress, this, &ParameterManager::_ftpDownloadProgress);
495
496 if (errorMsg.isEmpty()) {
497 qCDebug(ParameterManagerLog) << "ParameterManager::_ftpDownloadComplete : Parameter file received:" << fileName;
498 if (_parseParamFile(fileName)) {
499 qCDebug(ParameterManagerLog) << "ParameterManager::_ftpDownloadComplete : Parsed!";
500 return;
501 } else {
502 qCDebug(ParameterManagerLog) << "ParameterManager::_ftpDownloadComplete : Error in parameter file";
503 /* This should not happen... */
504 }
505 } else if (errorMsg.contains("File Not Found")) {
506 qCDebug(ParameterManagerLog) << "ParameterManager-ftp: No Parameterfile on vehicle - Start Conventional Parameter Download";
507 if (_initialRequestRetryCount == 0) {
508 immediateRetry = true;
509 }
510 } else if ((_loadProgress > 0.0001) && (_loadProgress < 0.01)) { /* FTP supported but too slow */
511 qCDebug(ParameterManagerLog) << "ParameterManager-ftp progress too slow - Start Conventional Parameter Download";
512 } else if (_initialRequestRetryCount == 1) {
513 qCDebug(ParameterManagerLog) << "ParameterManager-ftp: Too many retries - Start Conventional Parameter Download";
514 } else {
515 qCDebug(ParameterManagerLog) << "ParameterManager-ftp Retry:" << _initialRequestRetryCount;
516 continueWithDefaultParameterdownload = false;
517 }
518
519 if (continueWithDefaultParameterdownload) {
520 _tryftp = false;
521 _initialRequestRetryCount = 0;
522 /* If we receive "File not Found" this indicates that the vehicle does not support
523 * the parameter download via ftp. If we received this without retry, then we
524 * can immediately response with the conventional parameter download request, because
525 * we have no indication of communication link congestion.*/
526 if (immediateRetry) {
527 _paramRequestListTimeout();
528 } else {
529 _paramRequestListTimer.start();
530 }
531 } else {
532 _paramRequestListTimer.start();
533 }
534}
535
536void ParameterManager::_ftpDownloadProgress(float progress)
537{
538 qCDebug(ParameterManagerVerbose1Log) << "ParameterManager::_ftpDownloadProgress:" << progress;
539 _setLoadProgress(static_cast<double>(progress));
540 if (progress > 0.001) {
541 _paramRequestListTimer.stop();
542 }
543}
544
546{
547 const SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
548 if (!sharedLink) {
549 return;
550 }
551
552 if (sharedLink->linkConfiguration()->isHighLatency() || _logReplay) {
553 // These links don't load params
554 _parametersReady = true;
555 _missingParameters = true;
556 _initialLoadComplete = true;
557 _waitingForDefaultComponent = false;
558 emit parametersReadyChanged(_parametersReady);
559 emit missingParametersChanged(_missingParameters);
560 }
561
562 if (_tryftp && ((componentId == MAV_COMP_ID_ALL) || (componentId == MAV_COMP_ID_AUTOPILOT1))) {
563 if (!_initialLoadComplete) {
564 _paramRequestListTimer.start();
565 }
566 FTPManager *const ftpManager = _vehicle->ftpManager();
567 (void) connect(ftpManager, &FTPManager::downloadComplete, this, &ParameterManager::_ftpDownloadComplete);
568 _waitingParamTimeoutTimer.stop();
569 if (ftpManager->download(MAV_COMP_ID_AUTOPILOT1,
570 QStringLiteral("@PARAM/param.pck"),
571 QStandardPaths::writableLocation(QStandardPaths::TempLocation),
572 QStringLiteral(""),
573 false /* No filesize check */)) {
574 (void) connect(ftpManager, &FTPManager::commandProgress, this, &ParameterManager::_ftpDownloadProgress);
575 } else {
576 qCWarning(ParameterManagerLog) << "ParameterManager::refreshallParameters FTPManager::download returned failure";
577 (void) disconnect(ftpManager, &FTPManager::downloadComplete, this, &ParameterManager::_ftpDownloadComplete);
578 }
579 } else if (_vehicle->px4Firmware() && !_initialLoadComplete && !_hashCheckDone) {
580 // PX4: Try _HASH_CHECK first to see if we can load from cache without a full parameter stream
581 _hashCheckTimer.start();
582 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Requesting _HASH_CHECK before full parameter list";
583 const uint8_t hashCheckCompId = (componentId == MAV_COMP_ID_ALL)
584 ? static_cast<uint8_t>(MAV_COMP_ID_AUTOPILOT1)
585 : componentId;
586 _requestHashCheck(hashCheckCompId);
587 } else {
588 if (!_initialLoadComplete) {
589 _paramRequestListTimer.start();
590 }
591
592 // Reset index wait lists
593 for (int cid: _paramCountMap.keys()) {
594 // Add/Update all indices to the wait list, parameter index is 0-based
595 if ((componentId != MAV_COMP_ID_ALL) && (componentId != cid)) {
596 continue;
597 }
598 for (int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
599 // This will add a new waiting index if needed and set the retry count for that index to 0
600 _waitingReadParamIndexMap[cid][waitingIndex] = 0;
601 }
602 }
603
604 mavlink_message_t msg{};
605 mavlink_msg_param_request_list_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
607 sharedLink->mavlinkChannel(),
608 &msg,
609 _vehicle->id(),
610 componentId);
611 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
612 }
613
614 const QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId);
615 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what;
616}
617
618int ParameterManager::_actualComponentId(int componentId) const
619{
620 if (componentId == defaultComponentId) {
621 componentId = _vehicle->defaultComponentId();
622 if (componentId == defaultComponentId) {
623 qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "Default component id not set";
624 }
625 }
626
627 return componentId;
628}
629
630void ParameterManager::refreshParameter(int componentId, const QString &paramName)
631{
632 componentId = _actualComponentId(componentId);
633
634 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParameter - name:" << paramName << ")";
635
636 _mavlinkParamRequestRead(componentId, paramName, -1, true /* notifyFailure */);
637}
638
639void ParameterManager::refreshParametersPrefix(int componentId, const QString &namePrefix)
640{
641 componentId = _actualComponentId(componentId);
642 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "refreshParametersPrefix - name:" << namePrefix << ")";
643
644 for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
645 if (paramName.startsWith(namePrefix)) {
646 refreshParameter(componentId, paramName);
647 }
648 }
649}
650
651bool ParameterManager::parameterExists(int componentId, const QString &paramName) const
652{
653 bool ret = false;
654
655 componentId = _actualComponentId(componentId);
656 if (_mapCompId2FactMap.contains(componentId)) {
657 ret = _mapCompId2FactMap[componentId].contains(_remapParamNameToVersion(paramName));
658 }
659
660 return ret;
661}
662
663Fact *ParameterManager::getParameter(int componentId, const QString &paramName)
664{
665 componentId = _actualComponentId(componentId);
666
667 const QString mappedParamName = _remapParamNameToVersion(paramName);
668 if (!_mapCompId2FactMap.contains(componentId) || !_mapCompId2FactMap[componentId].contains(mappedParamName)) {
669 qgcApp()->reportMissingParameter(componentId, mappedParamName);
670 return &_defaultFact;
671 }
672
673 return _mapCompId2FactMap[componentId][mappedParamName];
674}
675
676QStringList ParameterManager::parameterNames(int componentId) const
677{
678 QStringList names;
679
680 const int compId = _actualComponentId(componentId);
681 const QMap<QString, Fact*> &factMap = _mapCompId2FactMap[compId];
682 for (const QString &paramName: factMap.keys()) {
683 names << paramName;
684 }
685
686 return names;
687}
688
689bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
690{
691 if (!_indexBatchQueueActive) {
692 return false;
693 }
694
695 constexpr int maxBatchSize = 10;
696
697 if (waitingParamTimeout) {
698 // We timed out, clear the queue and try again
699 qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to timeout";
700 _indexBatchQueue.clear();
701 } else {
702 qCDebug(ParameterManagerLog) << "Refilling index based batch queue due to received parameter";
703 }
704
705 for (const int componentId: _waitingReadParamIndexMap.keys()) {
706 if (_waitingReadParamIndexMap[componentId].count()) {
707 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count();
708 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId];
709 }
710
711 for (const int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
712 if (_indexBatchQueue.contains(paramIndex)) {
713 // Don't add more than once
714 continue;
715 }
716
717 if (_indexBatchQueue.count() > maxBatchSize) {
718 break;
719 }
720
721 _waitingReadParamIndexMap[componentId][paramIndex]++; // Bump retry count
722 if (_disableAllRetries || (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam)) {
723 // Give up on this index
724 _failedReadParamIndexMap[componentId] << paramIndex;
725 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Giving up on (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
726 (void) _waitingReadParamIndexMap[componentId].remove(paramIndex);
727 } else {
728 // Retry again
729 _indexBatchQueue.append(paramIndex);
730 _mavlinkParamRequestRead(componentId, QString(), paramIndex, false /* notifyFailure */);
731 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Read re-request for (paramIndex:" << paramIndex << "retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] << ")";
732 }
733 }
734 }
735
736 return (!_indexBatchQueue.isEmpty());
737}
738
739void ParameterManager::_waitingParamTimeout()
740{
741 if (_logReplay) {
742 return;
743 }
744
745 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout";
746
747 // Now that we have timed out for possibly the first time we can activate the index batch queue
748 _indexBatchQueueActive = true;
749
750 // First check for any missing parameters from the initial index based load
751 bool paramsRequested = _fillIndexBatchQueue(true /* waitingParamTimeout */);
752 if (!paramsRequested && !_waitingForDefaultComponent && !_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
753 // Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the
754 // any show up.
755 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId();
756 _waitingParamTimeoutTimer.start();
757 _waitingForDefaultComponent = true;
758 return;
759 }
760 _waitingForDefaultComponent = false;
761
762 _checkInitialLoadComplete();
763
764 if (paramsRequested) {
765 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request";
766 _waitingParamTimeoutTimer.start();
767 }
768}
769
770void ParameterManager::_requestHashCheck(uint8_t componentId)
771{
772 const SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
773 if (!sharedLink) {
774 return;
775 }
776
777 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Sending PARAM_REQUEST_READ for _HASH_CHECK";
778
779 char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1] = {};
780 (void) strncpy(paramId, "_HASH_CHECK", MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
781
782 mavlink_message_t msg{};
783 (void) mavlink_msg_param_request_read_pack_chan(
786 sharedLink->mavlinkChannel(),
787 &msg,
788 static_cast<uint8_t>(_vehicle->id()),
789 componentId,
790 paramId,
791 -1);
792
793 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
794}
795
796void ParameterManager::_mavlinkParamRequestRead(int componentId, const QString &paramName, int paramIndex, bool notifyFailure)
797{
798 auto paramRequestReadEncoder = [this, componentId, paramName, paramIndex](uint8_t /*systemId*/, uint8_t channel, mavlink_message_t *message) -> void {
799 char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1] = {};
800 (void) strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
801
802 (void) mavlink_msg_param_request_read_pack_chan(MAVLinkProtocol::instance()->getSystemId(), // QGC system id
803 MAVLinkProtocol::getComponentId(), // QGC component id
804 channel,
805 message,
806 static_cast<uint8_t>(_vehicle->id()),
807 static_cast<uint8_t>(componentId),
808 paramId,
809 static_cast<int16_t>(paramIndex));
810 };
811
812 auto checkForCorrectParamValue = [componentId, paramName, paramIndex](const mavlink_message_t &message) -> bool {
813 if (message.compid != componentId) {
814 return false;
815 }
816
817 mavlink_param_value_t param_value{};
818 mavlink_msg_param_value_decode(&message, &param_value);
819
820 // This will null terminate the name string
821 char parameterNameWithNull[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1] = {};
822 (void) strncpy(parameterNameWithNull, param_value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
823 const QString parameterName(parameterNameWithNull);
824
825 // Check that this is for the parameter we requested
826 if (paramIndex != -1) {
827 // Index based request
828 if (param_value.param_index != paramIndex) {
829 return false;
830 }
831 } else {
832 // Name based request
833 if (parameterName != paramName) {
834 return false;
835 }
836 }
837
838 return true;
839 };
840
841 // State Machine:
842 // Send PARAM_REQUEST_READ - 2 retries after initial attempt
843 // Wait for PARAM_VALUE ack
844 //
845 // timeout:
846 // Back up to PARAM_REQUEST_READ for retries
847 //
848 // error:
849 // Notify user of failure
850
851 // Create states
852 auto stateMachine = new QGCStateMachine(QStringLiteral("PARAM_REQUEST_READ"), vehicle(), this);
853 auto sendParamRequestReadState = new SendMavlinkMessageState(stateMachine, paramRequestReadEncoder, kParamRequestReadRetryCount);
854 auto waitAckState = new WaitForMavlinkMessageState(stateMachine, MAVLINK_MSG_ID_PARAM_VALUE, kWaitForParamValueAckMs, checkForCorrectParamValue);
855 auto userNotifyState = new ShowAppMessageState(stateMachine, QStringLiteral("Parameter read failed: param: %1 %2").arg(paramName).arg(_vehicleAndComponentString(componentId)));
856 auto logSuccessState = new FunctionState(QStringLiteral("Log success"), stateMachine, [this, componentId, paramName, paramIndex]() {
857 qCDebug(ParameterManagerLog) << "PARAM_REQUEST_READ succeeded: name:" << paramName << "index" << paramIndex << _vehicleAndComponentString(componentId);
858 emit _paramRequestReadSuccess(componentId, paramName, paramIndex);
859 });
860 auto logFailureState = new FunctionState(QStringLiteral("Log failure"), stateMachine, [this, componentId, paramName, paramIndex]() {
861 qCDebug(ParameterManagerLog) << "PARAM_REQUEST_READ failed: param:" << paramName << "index" << paramIndex << _vehicleAndComponentString(componentId);
862 emit _paramRequestReadFailure(componentId, paramName, paramIndex);
863 });
864 auto finalState = new QGCFinalState(stateMachine);
865
866 // Successful state machine transitions
867 stateMachine->setInitialState(sendParamRequestReadState);
868 sendParamRequestReadState->addThisTransition(&QGCState::advance, waitAckState);
869 waitAckState->addThisTransition (&QGCState::advance, logSuccessState);
870 logSuccessState->addThisTransition (&QGCState::advance, finalState);
871
872 // Retry transitions
873 waitAckState->addTransition(waitAckState, &WaitForMavlinkMessageState::timeout, sendParamRequestReadState); // Retry on timeout
874
875 // Error transitions
876 sendParamRequestReadState->addThisTransition(&QGCState::error, logFailureState); // Error is signaled after retries exhausted or internal error
877
878 // Error state branching transitions
879 if (notifyFailure) {
880 logFailureState->addThisTransition (&QGCState::advance, userNotifyState);
881 } else {
882 logFailureState->addThisTransition (&QGCState::advance, finalState);
883 }
884 userNotifyState->addThisTransition (&QGCState::advance, finalState);
885
886 qCDebug(ParameterManagerLog) << "Starting state machine for PARAM_REQUEST_READ on: " << paramName << _vehicleAndComponentString(componentId);
887 stateMachine->start();
888}
889
890void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
891{
892 CacheMapName2ParamTypeVal cacheMap;
893
894 for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
895 const Fact *const fact = _mapCompId2FactMap[componentId][paramName];
896 cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
897 }
898
899 QFile cacheFile(parameterCacheFile(vehicleId, componentId));
900 if (cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
901 QDataStream ds(&cacheFile);
902 ds << cacheMap;
903 } else {
904 qCWarning(ParameterManagerLog) << "Failed to open cache file for writing" << cacheFile.fileName();
905 }
906}
907
909{
910 // Use application-specific subdirectory to isolate parallel test runs
911 const QFileInfo settingsFile(QSettings().fileName());
912 const QString basePath = settingsFile.dir().absolutePath();
913 const QString appName = settingsFile.completeBaseName();
914 return QDir(basePath + QDir::separator() + appName + QDir::separator() + QStringLiteral("ParamCache"));
915}
916
917QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
918{
919 return parameterCacheDir().filePath(QStringLiteral("%1_%2.v2").arg(vehicleId).arg(componentId));
920}
921
922void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, const QVariant &hashValue)
923{
924 qCDebug(ParameterManagerLog) << "Attemping load from cache";
925
926 /* The datastructure of the cache table */
927 CacheMapName2ParamTypeVal cacheMap;
928 QFile cacheFile(parameterCacheFile(vehicleId, componentId));
929 if (!cacheFile.exists()) {
930 qCDebug(ParameterManagerLog) << "No parameter cache file";
931 if (!_hashCheckDone) {
932 // Standalone hash check path — fall back to PARAM_REQUEST_LIST
933 _hashCheckDone = true;
935 }
936 // If already in PARAM_REQUEST_LIST flow, just let the stream continue
937 return;
938 }
939 (void) cacheFile.open(QIODevice::ReadOnly);
940
941 /* Deserialize the parameter cache table */
942 QDataStream ds(&cacheFile);
943 ds >> cacheMap;
944
945 /* compute the crc of the local cache to check against the remote */
946 uint32_t crc32_value = 0;
947 for (const QString &name: cacheMap.keys()) {
948 const ParamTypeVal &paramTypeVal = cacheMap[name];
949 const FactMetaData::ValueType_t factType = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
950
951 if (_vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->factMetaDataForName(name, factType)->volatileValue()) {
952 // Does not take part in CRC
953 qCDebug(ParameterManagerLog) << "Volatile parameter" << name;
954 } else {
955 const void *const vdat = paramTypeVal.second.constData();
956 const FactMetaData::ValueType_t cacheFactType = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
957 crc32_value = QGC::crc32(reinterpret_cast<const uint8_t *>(qPrintable(name)), name.length(), crc32_value);
958 crc32_value = QGC::crc32(static_cast<const uint8_t *>(vdat), FactMetaData::typeToSize(cacheFactType), crc32_value);
959 }
960 }
961
962 /* if the two param set hashes match, just load from the disk */
963 if (crc32_value == hashValue.toUInt()) {
964 _hashCheckDone = true;
965 _paramRequestListTimer.stop();
966 qCDebug(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
967
968 const int count = cacheMap.count();
969 int index = 0;
970 for (const QString &name: cacheMap.keys()) {
971 const ParamTypeVal &paramTypeVal = cacheMap[name];
972 const FactMetaData::ValueType_t factType = static_cast<FactMetaData::ValueType_t>(paramTypeVal.first);
973 const MAV_PARAM_TYPE mavParamType = factTypeToMavType(factType);
974 _handleParamValue(componentId, name, count, index++, mavParamType, paramTypeVal.second);
975 }
976
977 const SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
978 if (sharedLink) {
979 mavlink_param_set_t p{};
980 mavlink_param_union_t union_value{};
981
982 // Return the hash value to notify we don't want any more updates
983 p.param_type = MAV_PARAM_TYPE_UINT32;
984 (void) strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id));
985 union_value.param_uint32 = crc32_value;
986 p.param_value = union_value.param_float;
987 p.target_system = static_cast<uint8_t>(_vehicle->id());
988 p.target_component = static_cast<uint8_t>(componentId);
989
990 mavlink_message_t msg{};
991 (void) mavlink_msg_param_set_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
993 sharedLink->mavlinkChannel(),
994 &msg,
995 &p);
996 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
997 }
998
999 // Give the user some feedback things loaded properly
1000 QVariantAnimation *const ani = new QVariantAnimation(this);
1001 ani->setEasingCurve(QEasingCurve::OutCubic);
1002 ani->setStartValue(0.0);
1003 ani->setEndValue(1.0);
1004 ani->setDuration(750);
1005
1006 (void) connect(ani, &QVariantAnimation::valueChanged, this, [this](const QVariant &value) {
1007 _setLoadProgress(value.toDouble());
1008 });
1009
1010 // Hide 500ms after animation finishes
1011 connect(ani, &QVariantAnimation::finished, this, [this] {
1012 QTimer::singleShot(500, this, [this] {
1013 _setLoadProgress(0);
1014 });
1015 });
1016
1017 ani->start(QAbstractAnimation::DeleteWhenStopped);
1018 } else {
1019 qCDebug(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
1020 if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
1021 _debugCacheCRC[componentId] = true;
1022 _debugCacheMap[componentId] = cacheMap;
1023 for (const QString &name: cacheMap.keys()) {
1024 _debugCacheParamSeen[componentId][name] = false;
1025 }
1026 qgcApp()->showAppMessage(tr("Parameter cache CRC match failed"));
1027 }
1028 if (!_hashCheckDone) {
1029 // Standalone hash check path — fall back to PARAM_REQUEST_LIST
1030 _hashCheckDone = true;
1032 }
1033 // If already in PARAM_REQUEST_LIST flow, just let the stream continue
1034 }
1035}
1036
1038{
1039 QString missingErrors;
1040 QString typeErrors;
1041
1042 while (!stream.atEnd()) {
1043 const QString line = stream.readLine();
1044 if (!line.startsWith("#")) {
1045 const QStringList wpParams = line.split("\t");
1046 const int lineMavId = wpParams.at(0).toInt();
1047 if (wpParams.size() == 5) {
1048 if (_vehicle->id() != lineMavId) {
1049 return QStringLiteral("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.").arg(lineMavId).arg(_vehicle->id());
1050 }
1051
1052 const int componentId = wpParams.at(1).toInt();
1053 const QString paramName = wpParams.at(2);
1054 const QString valStr = wpParams.at(3);
1055 const uint mavType = wpParams.at(4).toUInt();
1056
1057 if (!parameterExists(componentId, paramName)) {
1058 QString error;
1059 error += QStringLiteral("%1:%2").arg(componentId).arg(paramName);
1060 missingErrors += error;
1061 qCDebug(ParameterManagerLog) << "Skipped due to missing:" << error;
1062 continue;
1063 }
1064
1065 Fact *const fact = getParameter(componentId, paramName);
1066 if (fact->type() != mavTypeToFactType(static_cast<MAV_PARAM_TYPE>(mavType))) {
1067 QString error;
1068 error = QStringLiteral("%1:%2 ").arg(componentId).arg(paramName);
1069 typeErrors += error;
1070 qCDebug(ParameterManagerLog) << "Skipped due to type mismatch: %1" << error;
1071 continue;
1072 }
1073
1074 qCDebug(ParameterManagerLog) << "Updating parameter" << componentId << paramName << valStr;
1075 fact->setRawValue(valStr);
1076 }
1077 }
1078 }
1079
1080 QString errors;
1081
1082 if (!missingErrors.isEmpty()) {
1083 errors = tr("Parameters not loaded since they are not currently on the vehicle: %1\n").arg(missingErrors);
1084 }
1085
1086 if (!typeErrors.isEmpty()) {
1087 errors += tr("Parameters not loaded due to type mismatch: %1").arg(typeErrors);
1088 }
1089
1090 return errors;
1091}
1092
1093void ParameterManager::writeParametersToStream(QTextStream &stream) const
1094{
1095 stream << "# Onboard parameters for Vehicle " << _vehicle->id() << "\n";
1096 stream << "#\n";
1097
1098 stream << "# Stack: " << _vehicle->firmwareTypeString() << "\n";
1099 stream << "# Vehicle: " << _vehicle->vehicleTypeString() << "\n";
1100 stream << "# Version: "
1101 << _vehicle->firmwareMajorVersion() << "."
1102 << _vehicle->firmwareMinorVersion() << "."
1103 << _vehicle->firmwarePatchVersion() << " "
1104 << _vehicle->firmwareVersionTypeString() << "\n";
1105 stream << "# Git Revision: " << _vehicle->gitHash() << "\n";
1106
1107 stream << "#\n";
1108 stream << "# Vehicle-Id Component-Id Name Value Type\n";
1109
1110 for (const int componentId: _mapCompId2FactMap.keys()) {
1111 for (const QString &paramName: _mapCompId2FactMap[componentId].keys()) {
1112 const Fact *const fact = _mapCompId2FactMap[componentId][paramName];
1113 if (fact) {
1114 stream << _vehicle->id() << "\t" << componentId << "\t" << paramName << "\t" << fact->rawValueStringFullPrecision() << "\t" << QStringLiteral("%1").arg(factTypeToMavType(fact->type())) << "\n";
1115 } else {
1116 qCWarning(ParameterManagerLog) << "Internal error: missing fact";
1117 }
1118 }
1119 }
1120
1121 stream.flush();
1122}
1123
1125{
1126 switch (factType) {
1128 return MAV_PARAM_TYPE_UINT8;
1130 return MAV_PARAM_TYPE_INT8;
1132 return MAV_PARAM_TYPE_UINT16;
1134 return MAV_PARAM_TYPE_INT16;
1136 return MAV_PARAM_TYPE_UINT32;
1138 return MAV_PARAM_TYPE_UINT64;
1140 return MAV_PARAM_TYPE_INT64;
1142 return MAV_PARAM_TYPE_REAL32;
1144 return MAV_PARAM_TYPE_REAL64;
1145 default:
1146 qCWarning(ParameterManagerLog) << "Unsupported fact type" << factType;
1147 [[fallthrough]];
1149 return MAV_PARAM_TYPE_INT32;
1150 }
1151}
1152
1154{
1155 switch (mavType) {
1156 case MAV_PARAM_TYPE_UINT8:
1158 case MAV_PARAM_TYPE_INT8:
1160 case MAV_PARAM_TYPE_UINT16:
1162 case MAV_PARAM_TYPE_INT16:
1164 case MAV_PARAM_TYPE_UINT32:
1166 case MAV_PARAM_TYPE_UINT64:
1168 case MAV_PARAM_TYPE_INT64:
1170 case MAV_PARAM_TYPE_REAL32:
1172 case MAV_PARAM_TYPE_REAL64:
1174 default:
1175 qCWarning(ParameterManagerLog) << "Unsupported mav param type" << mavType;
1176 [[fallthrough]];
1177 case MAV_PARAM_TYPE_INT32:
1179 }
1180}
1181
1182void ParameterManager::_checkInitialLoadComplete()
1183{
1184 if (_initialLoadComplete) {
1185 return;
1186 }
1187
1188 for (const int componentId: _waitingReadParamIndexMap.keys()) {
1189 if (!_waitingReadParamIndexMap[componentId].isEmpty()) {
1190 // We are still waiting on some parameters, not done yet
1191 return;
1192 }
1193 }
1194
1195 if (!_mapCompId2FactMap.contains(_vehicle->defaultComponentId())) {
1196 // No default component params yet, not done yet
1197 return;
1198 }
1199
1200 // We aren't waiting for any more initial parameter updates, initial parameter loading is complete
1201 _initialLoadComplete = true;
1202
1203 // Parameter cache crc failure debugging
1204 for (const int componentId: _debugCacheParamSeen.keys()) {
1205 if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
1206 for (const QString &paramName: _debugCacheParamSeen[componentId].keys()) {
1207 if (!_debugCacheParamSeen[componentId][paramName]) {
1208 qCDebug(ParameterManagerLog) << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
1209 }
1210 }
1211 }
1212 }
1213 _debugCacheCRC.clear();
1214
1215 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete";
1216
1217 // Check for index based load failures
1218 QString indexList;
1219 bool initialLoadFailures = false;
1220 for (const int componentId: _failedReadParamIndexMap.keys()) {
1221 for (const int paramIndex: _failedReadParamIndexMap[componentId]) {
1222 if (initialLoadFailures) {
1223 indexList += ", ";
1224 }
1225 indexList += QStringLiteral("%1:%2").arg(componentId).arg(paramIndex);
1226 initialLoadFailures = true;
1227 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")";
1228 }
1229 }
1230
1231 _missingParameters = false;
1232 if (initialLoadFailures) {
1233 _missingParameters = true;
1234 const QString errorMsg = tr("%1 was unable to retrieve the full set of parameters from vehicle %2. "
1235 "This will cause %1 to be unable to display its full user interface. "
1236 "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. "
1237 "If you are using standard firmware, you may need to upgrade to a newer version to resolve the issue.").arg(QCoreApplication::applicationName()).arg(_vehicle->id());
1238 qCDebug(ParameterManagerLog) << errorMsg;
1239 qgcApp()->showAppMessage(errorMsg);
1240 if (!qgcApp()->runningUnitTests()) {
1241 qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries:" << indexList;
1242 }
1243 }
1244
1245 // Signal load complete
1246 _parametersReady = true;
1247 _vehicle->autopilotPlugin()->parametersReadyPreChecks();
1248 emit parametersReadyChanged(true);
1249 emit missingParametersChanged(_missingParameters);
1250}
1251
1252void ParameterManager::_hashCheckTimeout()
1253{
1254 _hashCheckDone = true;
1255 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_HASH_CHECK timed out, falling back to PARAM_REQUEST_LIST";
1257}
1258
1259void ParameterManager::_paramRequestListTimeout()
1260{
1261 if (_logReplay) {
1262 // Signal load complete
1263 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_paramRequestListTimeout (log replay): Signalling load complete";
1264 _initialLoadComplete = true;
1265 _missingParameters = false;
1266 _parametersReady = true;
1267 _vehicle->autopilotPlugin()->parametersReadyPreChecks();
1268 emit parametersReadyChanged(true);
1269 emit missingParametersChanged(_missingParameters);
1270 return;
1271 }
1272
1273 if (!_disableAllRetries && (++_initialRequestRetryCount <= _maxInitialRequestListRetry)) {
1274 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Retrying initial parameter request list";
1276 } else if (!_vehicle->genericFirmware()) {
1277 const QString errorMsg = tr("Vehicle %1 did not respond to request for parameters. "
1278 "This will cause %2 to be unable to display its full user interface.").arg(_vehicle->id()).arg(QCoreApplication::applicationName());
1279 qCDebug(ParameterManagerLog) << errorMsg;
1280 qgcApp()->showAppMessage(errorMsg);
1281 }
1282}
1283
1284QString ParameterManager::_remapParamNameToVersion(const QString &paramName) const
1285{
1286 if (!paramName.startsWith(QStringLiteral("r."))) {
1287 // No version mapping wanted
1288 return paramName;
1289 }
1290
1291 const int majorVersion = _vehicle->firmwareMajorVersion();
1292 const int minorVersion = _vehicle->firmwareMinorVersion();
1293
1294 qCDebug(ParameterManagerLog) << "_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1295
1296 QString mappedParamName = paramName.right(paramName.length() - 2);
1297 if (majorVersion == Vehicle::versionNotSetValue) {
1298 // Vehicle version unknown
1299 return mappedParamName;
1300 }
1301
1303 if (!majorVersionRemap.contains(majorVersion)) {
1304 // No mapping for this major version
1305 qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: no major version mapping";
1306 return mappedParamName;
1307 }
1308
1309 const FirmwarePlugin::remapParamNameMinorVersionRemapMap_t &remapMinorVersion = majorVersionRemap[majorVersion];
1310 // We must map backwards from the highest known minor version to one above the vehicle's minor version
1311 for (int currentMinorVersion = _vehicle->firmwarePlugin()->remapParamNameHigestMinorVersionNumber(majorVersion); currentMinorVersion>minorVersion; currentMinorVersion--) {
1312 if (remapMinorVersion.contains(currentMinorVersion)) {
1313 const FirmwarePlugin::remapParamNameMap_t &remap = remapMinorVersion[currentMinorVersion];
1314 if (remap.contains(mappedParamName)) {
1315 const QString toParamName = remap[mappedParamName];
1316 qCDebug(ParameterManagerLog) << "_remapParamNameToVersion: remapped currentMinor:from:to" << currentMinorVersion << mappedParamName << toParamName;
1317 mappedParamName = toParamName;
1318 }
1319 }
1320 }
1321
1322 return mappedParamName;
1323}
1324
1325void ParameterManager::_loadOfflineEditingParams()
1326{
1327 const QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle);
1328 if (paramFilename.isEmpty()) {
1329 return;
1330 }
1331
1332 QFile paramFile(paramFilename);
1333 if (!paramFile.open(QFile::ReadOnly)) {
1334 qCWarning(ParameterManagerLog) << "Unable to open offline editing params file" << paramFilename;
1335 }
1336
1337 QTextStream paramStream(&paramFile);
1338 while (!paramStream.atEnd()) {
1339 const QString line = paramStream.readLine();
1340 if (line.startsWith("#")) {
1341 continue;
1342 }
1343
1344 const QStringList paramData = line.split("\t");
1345 Q_ASSERT(paramData.count() == 5);
1346
1347 const int offlineDefaultComponentId = paramData.at(1).toInt();
1348 _vehicle->setOfflineEditingDefaultComponentId(offlineDefaultComponentId);
1349 const QString paramName = paramData.at(2);
1350 const QString valStr = paramData.at(3);
1351 const MAV_PARAM_TYPE paramType = static_cast<MAV_PARAM_TYPE>(paramData.at(4).toUInt());
1352
1353 QVariant paramValue;
1354 switch (paramType) {
1355 case MAV_PARAM_TYPE_REAL32:
1356 paramValue = QVariant(valStr.toFloat());
1357 break;
1358 case MAV_PARAM_TYPE_UINT32:
1359 paramValue = QVariant(valStr.toUInt());
1360 break;
1361 case MAV_PARAM_TYPE_UINT16:
1362 paramValue = QVariant((quint16)valStr.toUInt());
1363 break;
1364 case MAV_PARAM_TYPE_INT16:
1365 paramValue = QVariant((qint16)valStr.toInt());
1366 break;
1367 case MAV_PARAM_TYPE_UINT8:
1368 paramValue = QVariant((quint8)valStr.toUInt());
1369 break;
1370 case MAV_PARAM_TYPE_INT8:
1371 paramValue = QVariant((qint8)valStr.toUInt());
1372 break;
1373 default:
1374 qCCritical(ParameterManagerLog) << "Unknown type" << paramType;
1375 [[fallthrough]];
1376 case MAV_PARAM_TYPE_INT32:
1377 paramValue = QVariant(valStr.toInt());
1378 break;
1379 }
1380
1381 Fact *const fact = new Fact(offlineDefaultComponentId, paramName, mavTypeToFactType(paramType), this);
1382
1383 FactMetaData *const factMetaData = _vehicle->compInfoManager()->compInfoParam(offlineDefaultComponentId)->factMetaDataForName(paramName, fact->type());
1384 fact->setMetaData(factMetaData);
1385
1386 _mapCompId2FactMap[defaultComponentId][paramName] = fact;
1387 }
1388
1389 _parametersReady = true;
1390 _initialLoadComplete = true;
1391 _debugCacheCRC.clear();
1392}
1393
1395{
1396 _vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1,
1397 MAV_CMD_PREFLIGHT_STORAGE,
1398 true, // showError
1399 2, // Reset params to default
1400 -1); // Don't do anything with mission storage
1401}
1402
1404{
1405 //-- https://github.com/PX4/Firmware/pull/11760
1406 Fact *const sysAutoConfigFact = getParameter(defaultComponentId, "SYS_AUTOCONFIG");
1407 if (sysAutoConfigFact) {
1408 sysAutoConfigFact->setRawValue(2);
1409 }
1410}
1411
1412QString ParameterManager::_logVehiclePrefix(int componentId) const
1413{
1414 if (componentId == -1) {
1415 return QStringLiteral("V:%1").arg(_vehicle->id());
1416 } else {
1417 return QStringLiteral("V:%1 C:%2").arg(_vehicle->id()).arg(componentId);
1418 }
1419}
1420
1421void ParameterManager::_setLoadProgress(double loadProgress)
1422{
1423 if (_loadProgress != loadProgress) {
1424 _loadProgress = loadProgress;
1425 emit loadProgressChanged(static_cast<float>(loadProgress));
1426 }
1427}
1428
1430{
1431 return _paramCountMap.keys();
1432}
1433
1435{
1436 return _pendingWritesCount > 0;
1437}
1438
1440{
1441 return _vehicle;
1442}
1443
1444
1445bool ParameterManager::_parseParamFile(const QString& filename)
1446{
1447 constexpr quint16 magic_standard = 0x671B;
1448 constexpr quint16 magic_withdefaults = 0x671C;
1449 quint32 no_of_parameters_found = 0;
1450 constexpr int componentId = MAV_COMP_ID_AUTOPILOT1;
1451 enum ap_var_type {
1452 AP_PARAM_NONE = 0,
1453 AP_PARAM_INT8,
1454 AP_PARAM_INT16,
1455 AP_PARAM_INT32,
1456 AP_PARAM_FLOAT,
1457 AP_PARAM_VECTOR3F,
1458 AP_PARAM_GROUP
1459 };
1460
1461 qCDebug(ParameterManagerLog) << "_parseParamFile:" << filename;
1462 QFile file(filename);
1463 if (!file.open(QIODevice::ReadOnly)) {
1464 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: Could not open downloaded parameter file.";
1465 return false;
1466 }
1467
1468 QDataStream in(&file);
1469 in.setByteOrder(QDataStream::LittleEndian);
1470
1471 quint16 magic, num_params, total_params;
1472 in >> magic;
1473 in >> num_params;
1474 in >> total_params;
1475
1476 if (in.status() != QDataStream::Ok) {
1477 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: Could not read Header";
1478 goto Error;
1479 }
1480
1481 qCDebug(ParameterManagerVerbose2Log) << "_parseParamFile: magic: 0x" << Qt::hex << magic;
1482 qCDebug(ParameterManagerVerbose2Log) << "_parseParamFile: num_params:" << num_params
1483 << "total_params:" << total_params;
1484
1485 if ((magic != magic_standard) && (magic != magic_withdefaults)) {
1486 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: File does not start with Magic";
1487 goto Error;
1488 }
1489 if (num_params > total_params) {
1490 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: total_params > num_params";
1491 goto Error;
1492 }
1493 if (num_params != total_params) {
1494 /* We requested all parameters, so this is an error here */
1495 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: total_params != num_params";
1496 goto Error;
1497 }
1498
1499 while (in.status() == QDataStream::Ok) {
1500 quint8 byte = 0;
1501 quint8 flags = 0;
1502 quint8 ptype = 0;
1503 quint8 name_len = 0;
1504 quint8 common_len = 0;
1505 bool withdefault = false;
1506 int no_read = 0;
1507 char name_buffer[17];
1508
1509 while (byte == 0x0) { // Eat padding bytes
1510 in >> byte;
1511 if (in.status() != QDataStream::Ok) {
1512 if (no_of_parameters_found == num_params) {
1513 goto Success;
1514 } else {
1515 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: unexpected EOF"
1516 << "number of parameters expected:" << num_params
1517 << "actual:" << no_of_parameters_found;
1518 goto Error;
1519 }
1520 }
1521 }
1522 ptype = byte & 0x0F;
1523 flags = (byte >> 4) & 0x0F;
1524 withdefault = (flags & 0x01) == 0x01;
1525 in >> byte;
1526 if (in.status() != QDataStream::Ok) {
1527 qCritical(ParameterManagerLog) << "_parseParamFile: Error: Unexpected EOF while reading flags";
1528 goto Error;
1529 }
1530 name_len = ((byte >> 4) & 0x0F) + 1;
1531 common_len = byte & 0x0F;
1532 if ((name_len + common_len) > 16) {
1533 qCritical(ParameterManagerLog) << "_parseParamFile: Error: common_len + name_len > 16"
1534 << "name_len" << name_len
1535 << "common_len" << common_len;
1536 goto Error;
1537 }
1538 no_read = in.readRawData(&name_buffer[common_len], static_cast<int>(name_len));
1539 if (no_read != name_len) {
1540 qCritical(ParameterManagerLog) << "_parseParamFile: Error: Unexpected EOF while reading parameterName"
1541 << "Expected:" << name_len
1542 << "Actual:" << no_read;
1543 goto Error;
1544 }
1545 name_buffer[common_len + name_len] = '\0';
1546 const QString parameterName(name_buffer);
1547 qCDebug(ParameterManagerVerbose2Log) << "_parseParamFile: parameter" << parameterName
1548 << "name_len" << name_len
1549 << "common_len" << common_len
1550 << "ptype" << ptype
1551 << "flags" << flags;
1552
1553 QVariant parameterValue = 0;
1554 switch (static_cast<ap_var_type>(ptype)) {
1555 qint8 data8;
1556 qint16 data16;
1557 qint32 data32;
1558 float dfloat;
1559 case AP_PARAM_INT8:
1560 in >> data8;
1561 parameterValue = data8;
1562 if (withdefault) {
1563 in >> data8;
1564 }
1565 break;
1566 case AP_PARAM_INT16:
1567 in >> data16;
1568 parameterValue = data16;
1569 if (withdefault) {
1570 in >> data16;
1571 }
1572 break;
1573 case AP_PARAM_INT32:
1574 in >> data32;
1575 parameterValue = data32;
1576 if (withdefault) {
1577 in >> data32;
1578 }
1579 break;
1580 case AP_PARAM_FLOAT:
1581 in >> data32;
1582 (void) memcpy(&dfloat, &data32, 4);
1583 parameterValue = dfloat;
1584 if (withdefault) {
1585 in >> data32;
1586 }
1587 break;
1588 default:
1589 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: type is out of range" << ptype;
1590 goto Error;
1591 break;
1592 }
1593 qCDebug(ParameterManagerVerbose2Log) << "paramValue" << parameterValue;
1594
1595 if (++no_of_parameters_found > num_params) {
1596 qCDebug(ParameterManagerLog) << "_parseParamFile: Error: more parameters in file than expected."
1597 << "Expected:" << num_params
1598 << "Actual:" << no_of_parameters_found;
1599 goto Error;
1600 }
1601
1602 const FactMetaData::ValueType_t factType = ((ptype == AP_PARAM_INT8) ? FactMetaData::valueTypeInt8 :
1603 (ptype == AP_PARAM_INT16) ? FactMetaData::valueTypeInt16 :
1604 (ptype == AP_PARAM_INT32) ? FactMetaData::valueTypeInt32 :
1605 FactMetaData::valueTypeFloat);
1606
1607 Fact *fact = nullptr;
1608 if (_mapCompId2FactMap.contains(componentId) && _mapCompId2FactMap[componentId].contains(parameterName)) {
1609 fact = _mapCompId2FactMap[componentId][parameterName];
1610 } else {
1611 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Adding new fact" << parameterName;
1612
1613 fact = new Fact(componentId, parameterName, factType, this);
1614 FactMetaData *const factMetaData = _vehicle->compInfoManager()->compInfoParam(componentId)->factMetaDataForName(parameterName, fact->type());
1615 fact->setMetaData(factMetaData);
1616
1617 _mapCompId2FactMap[componentId][parameterName] = fact;
1618
1619 // We need to know when the fact value changes so we can update the vehicle
1620 (void) connect(fact, &Fact::containerRawValueChanged, this, &ParameterManager::_factRawValueUpdated);
1621
1622 emit factAdded(componentId, fact);
1623 }
1624 fact->containerSetRawValue(parameterValue);
1625 }
1626
1627Success:
1628 file.close();
1629 /* Create empty waiting lists as we have all parameters */
1630 _paramCountMap[componentId] = num_params;
1631 _totalParamCount += num_params;
1632 _waitingReadParamIndexMap[componentId] = QMap<int, int>();
1633 _checkInitialLoadComplete();
1634 _setLoadProgress(0.0);
1635 return true;
1636
1637Error:
1638 file.close();
1639 return false;
1640}
1641
1642void ParameterManager::_incrementPendingWriteCount()
1643{
1644 _pendingWritesCount++;
1645 if (_pendingWritesCount == 1) {
1646 emit pendingWritesChanged(true);
1647 }
1648}
1649
1650void ParameterManager::_decrementPendingWriteCount()
1651{
1652 if (_pendingWritesCount == 0) {
1653 qCWarning(ParameterManagerLog) << "Internal Error: _pendingWriteCount == 0";
1654 return;
1655 }
1656
1657 _pendingWritesCount--;
1658 if (_pendingWritesCount == 0) {
1659 emit pendingWritesChanged(false);
1660 }
1661}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
Error error
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
FactMetaData * factMetaDataForName(const QString &name, FactMetaData::ValueType_t valueType)
CompInfoParam * compInfoParam(uint8_t compId)
void commandProgress(float value)
void downloadComplete(const QString &file, const QString &errorMsg)
bool download(uint8_t fromCompId, const QString &fromURI, const QString &toDir, const QString &fileName="", bool checksize=true)
Definition FTPManager.cc:29
static size_t typeToSize(ValueType_t type)
bool volatileValue() const
A Fact is used to hold a single value within the system.
Definition Fact.h:19
void containerRawValueChanged(const QVariant &value)
This signal is meant for use by Fact container implementations. Used to send changed values to vehicl...
QMap< int, remapParamNameMap_t > remapParamNameMinorVersionRemapMap_t
virtual int remapParamNameHigestMinorVersionNumber(int) const
Returns the highest major version number that is known to the remap for this specified major version.
QMap< QString, QString > remapParamNameMap_t
virtual QString offlineEditingParamFile(Vehicle *) const
Return the resource file which contains the set of params loaded for offline editing.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
virtual const remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const
Returns the mapping structure which is used to map from one parameter name to another based on firmwa...
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
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)
Fact * getParameter(int componentId, const QString &paramName)
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()
void missingParametersChanged(bool missingParameters)
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)
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.
void resetAllToVehicleConfiguration()
static QString parameterCacheFile(int vehicleId, int componentId)
void writeParametersToStream(QTextStream &stream) const
void _paramSetFailure(int componentId, const QString &paramName)
Final state for a QGCStateMachine with logging support.
QGroundControl specific state machine with enhanced error handling.
QSignalTransition * addThisTransition(PointerToMemberFunction signal, QAbstractState *target)
Simpler version of QState::addTransition which assumes the sender is this.
Definition QGCState.h:30
Sends the specified MAVLink message to the vehicle.
Display an application message to the user.
WeakLinkInterfacePtr primaryLink() const
bool px4Firmware() const
Definition Vehicle.h:495
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2309
static const int versionNotSetValue
Definition Vehicle.h:702
QString firmwareVersionTypeString() const
Definition Vehicle.cc:3182
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
ComponentInformationManager * compInfoManager()
Definition Vehicle.h:582
int firmwareMinorVersion() const
Definition Vehicle.h:691
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470
QString gitHash() const
Definition Vehicle.h:704
int defaultComponentId() const
Definition Vehicle.h:711
bool genericFirmware() const
Definition Vehicle.h:497
AutoPilotPlugin * autopilotPlugin()
Provides access to AutoPilotPlugin for this vehicle.
Definition Vehicle.h:441
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
Definition Vehicle.cc:3351
int firmwarePatchVersion() const
Definition Vehicle.h:692
QString firmwareTypeString() const
Definition Vehicle.cc:451
FTPManager * ftpManager()
Definition Vehicle.h:581
int firmwareMajorVersion() const
Definition Vehicle.h:690
QString vehicleTypeString() const
Definition Vehicle.cc:1874
Error
Error codes for decompression operations.
quint32 crc32(const quint8 *src, unsigned len, unsigned state)
Definition QGC.cc:97
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGC.cc:106