16#include <QtCore/QEasingCurve>
17#include <QtCore/QFile>
18#include <QtCore/QStandardPaths>
19#include <QtCore/QVariantAnimation>
29 , _logReplay(!vehicle->vehicleLinkManager()->primaryLink().expired() && vehicle->vehicleLinkManager()->primaryLink().lock()->isLogReplay())
30 , _disableAllRetries(_logReplay)
31 , _tryftp(vehicle->apmFirmware())
33 qCDebug(ParameterManagerLog) <<
this;
35 if (_vehicle->isOfflineEditingVehicle()) {
36 _loadOfflineEditingParams();
41 qCDebug(ParameterManagerLog) <<
this <<
"In log replay mode";
44 _hashCheckTimer.setSingleShot(
true);
45 _hashCheckTimer.setInterval(kHashCheckTimeoutMs);
46 (void) connect(&_hashCheckTimer, &QTimer::timeout,
this, &ParameterManager::_hashCheckTimeout);
48 _paramRequestListTimer.setSingleShot(
true);
49 _paramRequestListTimer.setInterval(
qgcApp()->runningUnitTests() ? kTestInitialRequestIntervalMs : kParamRequestListTimeoutMs);
50 (void) connect(&_paramRequestListTimer, &QTimer::timeout,
this, &ParameterManager::_paramRequestListTimeout);
52 _waitingParamTimeoutTimer.setSingleShot(
true);
53 _waitingParamTimeoutTimer.setInterval(
qgcApp()->runningUnitTests() ? 500 : 3000);
55 (void) connect(&_waitingParamTimeoutTimer, &QTimer::timeout,
this, &ParameterManager::_waitingParamTimeout);
59 (void) QDir().mkpath(parameterCacheDir().absolutePath());
64 qCDebug(ParameterManagerLog) <<
this;
67void ParameterManager::_updateProgressBar()
69 int waitingReadParamIndexCount = 0;
71 for (
const int compId: _waitingReadParamIndexMap.keys()) {
72 waitingReadParamIndexCount += _waitingReadParamIndexMap[compId].count();
75 if (waitingReadParamIndexCount == 0) {
76 if (_readParamIndexProgressActive) {
77 _readParamIndexProgressActive =
false;
78 _setLoadProgress(0.0);
82 _readParamIndexProgressActive =
true;
83 _setLoadProgress(
static_cast<double>(_totalParamCount - waitingReadParamIndexCount) /
static_cast<double>(_totalParamCount));
90 if (_tryftp && (message.compid == MAV_COMP_ID_AUTOPILOT1) && !_initialLoadComplete)
93 if (message.msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
94 mavlink_param_value_t param_value{};
95 mavlink_msg_param_value_decode(&message, ¶m_value);
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);
102 mavlink_param_union_t paramUnion{};
103 paramUnion.param_float = param_value.param_value;
104 paramUnion.type = param_value.param_type;
106 QVariant parameterValue;
107 if (!_mavlinkParamUnionToVariant(paramUnion, parameterValue)) {
111 _handleParamValue(message.compid, parameterName, param_value.param_count, param_value.param_index,
static_cast<MAV_PARAM_TYPE
>(param_value.param_type), parameterValue);
115void ParameterManager::_handleParamValue(
int componentId,
const QString ¶meterName,
int parameterCount,
int parameterIndex, MAV_PARAM_TYPE mavParamType,
const QVariant ¶meterValue)
118 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
119 "_parameterUpdate" <<
120 "name:" << parameterName <<
121 "count:" << parameterCount <<
122 "index:" << parameterIndex <<
123 "mavType:" << mavParamType <<
124 "value:" << parameterValue <<
129 if ((parameterIndex == 65535) && (parameterName != QStringLiteral(
"_HASH_CHECK")) && _paramRequestListTimer.isActive()) {
130 qCDebug(ParameterManagerLog) <<
"Disregarding unrequested param prior to initial list response" << parameterName;
134 if (_vehicle->
px4Firmware() && (parameterName ==
"_HASH_CHECK")) {
135 _hashCheckTimer.stop();
136 if (!_initialLoadComplete && !_logReplay) {
138 _tryCacheHashLoad(_vehicle->
id(), componentId, parameterValue);
143 _paramRequestListTimer.stop();
146 if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
147 if (_debugCacheMap[componentId].contains(parameterName)) {
148 const ParamTypeVal &cacheParamTypeVal = _debugCacheMap[componentId][parameterName];
150 const void *
const cacheData = cacheParamTypeVal.second.constData();
151 const void *
const vehicleData = parameterValue.constData();
153 if (memcmp(cacheData, vehicleData, dataSize) != 0) {
154 qCDebug(ParameterManagerVerbose1Log) <<
"Cache/Vehicle values differ for name:cache:actual" << parameterName << parameterValue << cacheParamTypeVal.second;
156 _debugCacheParamSeen[componentId][parameterName] =
true;
158 qCDebug(ParameterManagerVerbose1Log) <<
"Parameter missing from cache" << parameterName;
162 _waitingParamTimeoutTimer.stop();
165 if (!_paramCountMap.contains(componentId)) {
166 _paramCountMap[componentId] = parameterCount;
167 _totalParamCount += parameterCount;
171 if (!_waitingReadParamIndexMap.contains(componentId)) {
173 for (
int waitingIndex = 0; waitingIndex < parameterCount; waitingIndex++) {
175 _waitingReadParamIndexMap[componentId][waitingIndex] = 0;
178 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"Seeing component for first time - paramcount:" << parameterCount;
181 if (!_waitingReadParamIndexMap[componentId].contains(parameterIndex)) {
182 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"Unrequested param update" << parameterName;
186 if (_waitingReadParamIndexMap[componentId].contains(parameterIndex)) {
187 _waitingReadParamIndexMap[componentId].remove(parameterIndex);
188 (void) _indexBatchQueue.removeOne(parameterIndex);
189 _fillIndexBatchQueue(
false );
193 int waitingReadParamIndexCount = 0;
195 for (
const int waitingComponentId: _waitingReadParamIndexMap.keys()) {
196 waitingReadParamIndexCount += _waitingReadParamIndexMap[waitingComponentId].count();
198 if (waitingReadParamIndexCount) {
199 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"waitingReadParamIndexCount:" << waitingReadParamIndexCount;
202 const int readWaitingParamCount = waitingReadParamIndexCount;
203 const int totalWaitingParamCount = readWaitingParamCount;
204 if (totalWaitingParamCount) {
206 _waitingParamTimeoutTimer.start();
207 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) <<
"Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount;
210 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Restarting _waitingParamTimeoutTimer (still waiting for default component params)";
211 _waitingParamTimeoutTimer.start();
213 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) <<
"Not restarting _waitingParamTimeoutTimer (all requests satisfied)";
216 _updateProgressBar();
218 Fact *fact =
nullptr;
219 if (_mapCompId2FactMap.contains(componentId) && _mapCompId2FactMap[componentId].contains(parameterName)) {
220 fact = _mapCompId2FactMap[componentId][parameterName];
222 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"Adding new fact" << parameterName;
226 fact->setMetaData(factMetaData);
228 _mapCompId2FactMap[componentId][parameterName] = fact;
236 fact->containerSetRawValue(parameterValue);
242 if (_prevWaitingReadParamIndexCount != 0 && readWaitingParamCount == 0) {
244 _writeLocalParamCache(_vehicle->
id(), componentId);
248 _prevWaitingReadParamIndexCount = waitingReadParamIndexCount;
250 _checkInitialLoadComplete();
252 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"_parameterUpdate complete";
255QString ParameterManager::_vehicleAndComponentString(
int componentId)
const
258 QString vehicleIdStr;
259 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
260 vehicleIdStr = QStringLiteral(
"veh: %1").arg(_vehicle->
id());
264 QString componentIdStr;
265 if (_mapCompId2FactMap.keys().count() > 1) {
266 componentIdStr = QStringLiteral(
"comp: %1").arg(componentId);
269 if (!vehicleIdStr.isEmpty() && !componentIdStr.isEmpty()) {
270 return vehicleIdStr + QStringLiteral(
" ") + componentIdStr;
271 }
else if (!vehicleIdStr.isEmpty()) {
273 }
else if (!componentIdStr.isEmpty()) {
274 return componentIdStr;
280void ParameterManager::_mavlinkParamSet(
int componentId,
const QString ¶mName,
FactMetaData::ValueType_t valueType,
const QVariant &rawValue)
282 auto paramSetEncoder = [
this, componentId, paramName, valueType, rawValue](uint8_t , uint8_t channel,
mavlink_message_t *message) ->
void {
285 mavlink_param_union_t union_value{};
286 if (!_fillMavlinkParamUnion(valueType, rawValue, union_value)) {
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);
293 (void) mavlink_msg_param_set_pack_chan(
298 static_cast<uint8_t
>(_vehicle->
id()),
299 static_cast<uint8_t
>(componentId),
301 union_value.param_float,
302 static_cast<uint8_t
>(paramType));
305 auto checkForCorrectParamValue = [
this, componentId, paramName, rawValue](
const mavlink_message_t &message) ->
bool {
306 if (message.compid != componentId) {
310 mavlink_param_value_t param_value{};
311 mavlink_msg_param_value_decode(&message, ¶m_value);
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);
318 if (parameterName != paramName) {
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)) {
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();
334 if (param_value.param_type == MAV_PARAM_TYPE_REAL32) {
338 return receivedValue == rawValue;
359 auto incPendingWriteCountState =
new FunctionState(QStringLiteral(
"ParameterManager increment pending write count"), stateMachine, [
this]() {
360 _incrementPendingWriteCount();
362 auto decPendingWriteCountState =
new FunctionState(QStringLiteral(
"ParameterManager decrement pending write count"), stateMachine, [
this]() {
363 _decrementPendingWriteCount();
365 auto retryDecPendingWriteCountState =
new FunctionState(QStringLiteral(
"ParameterManager retry decrement pending write count"), stateMachine, [
this]() {
366 _decrementPendingWriteCount();
369 auto paramRefreshState =
new FunctionState(QStringLiteral(
"ParameterManager param refresh"), stateMachine, [
this, componentId, paramName]() {
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);
377 auto logFailureState =
new FunctionState(QStringLiteral(
"ParameterManager log failure"), stateMachine, [
this, componentId, paramName]() {
378 qCDebug(ParameterManagerLog) <<
"Parameter write failed: param:" << paramName << _vehicleAndComponentString(componentId);
384 stateMachine->setInitialState(sendParamSetState);
385 sendParamSetState->addThisTransition (&
QGCState::advance, incPendingWriteCountState);
396 sendParamSetState->addThisTransition(&
QGCState::error, logFailureState);
403 qCDebug(ParameterManagerLog) <<
"Starting state machine for PARAM_SET on: " << paramName << _vehicleAndComponentString(componentId);
404 stateMachine->start();
407bool ParameterManager::_fillMavlinkParamUnion(
FactMetaData::ValueType_t valueType,
const QVariant &rawValue, mavlink_param_union_t ¶mUnion)
const
413 paramUnion.param_uint8 =
static_cast<uint8_t
>(rawValue.toUInt(&ok));
416 paramUnion.param_int8 =
static_cast<int8_t
>(rawValue.toInt(&ok));
419 paramUnion.param_uint16 =
static_cast<uint16_t
>(rawValue.toUInt(&ok));
422 paramUnion.param_int16 =
static_cast<int16_t
>(rawValue.toInt(&ok));
425 paramUnion.param_uint32 =
static_cast<uint32_t
>(rawValue.toUInt(&ok));
428 paramUnion.param_float = rawValue.toFloat(&ok);
431 paramUnion.param_int32 =
static_cast<int32_t
>(rawValue.toInt(&ok));
434 qCCritical(ParameterManagerLog) <<
"Internal Error: Unsupported fact value type" << valueType;
435 paramUnion.param_int32 =
static_cast<int32_t
>(rawValue.toInt(&ok));
440 qCCritical(ParameterManagerLog) <<
"Fact Failed to Convert to Param Type:" << valueType;
447bool ParameterManager::_mavlinkParamUnionToVariant(
const mavlink_param_union_t ¶mUnion, QVariant &outValue)
const
449 switch (paramUnion.type) {
450 case MAV_PARAM_TYPE_REAL32:
451 outValue = QVariant(paramUnion.param_float);
453 case MAV_PARAM_TYPE_UINT8:
454 outValue = QVariant(paramUnion.param_uint8);
456 case MAV_PARAM_TYPE_INT8:
457 outValue = QVariant(paramUnion.param_int8);
459 case MAV_PARAM_TYPE_UINT16:
460 outValue = QVariant(paramUnion.param_uint16);
462 case MAV_PARAM_TYPE_INT16:
463 outValue = QVariant(paramUnion.param_int16);
465 case MAV_PARAM_TYPE_UINT32:
466 outValue = QVariant(paramUnion.param_uint32);
468 case MAV_PARAM_TYPE_INT32:
469 outValue = QVariant(paramUnion.param_int32);
472 qCCritical(ParameterManagerLog) <<
"ParameterManager::_mavlinkParamUnionToVariant - unsupported MAV_PARAM_TYPE" << paramUnion.type;
477void ParameterManager::_factRawValueUpdated(
const QVariant &rawValue)
479 Fact *
const fact = qobject_cast<Fact*>(sender());
481 qCWarning(ParameterManagerLog) <<
"Internal error";
485 _mavlinkParamSet(fact->componentId(), fact->name(), fact->type(), rawValue);
488void ParameterManager::_ftpDownloadComplete(
const QString &fileName,
const QString &errorMsg)
490 bool continueWithDefaultParameterdownload =
true;
491 bool immediateRetry =
false;
496 if (errorMsg.isEmpty()) {
497 qCDebug(ParameterManagerLog) <<
"ParameterManager::_ftpDownloadComplete : Parameter file received:" << fileName;
498 if (_parseParamFile(fileName)) {
499 qCDebug(ParameterManagerLog) <<
"ParameterManager::_ftpDownloadComplete : Parsed!";
502 qCDebug(ParameterManagerLog) <<
"ParameterManager::_ftpDownloadComplete : Error in parameter file";
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;
510 }
else if ((_loadProgress > 0.0001) && (_loadProgress < 0.01)) {
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";
515 qCDebug(ParameterManagerLog) <<
"ParameterManager-ftp Retry:" << _initialRequestRetryCount;
516 continueWithDefaultParameterdownload =
false;
519 if (continueWithDefaultParameterdownload) {
521 _initialRequestRetryCount = 0;
526 if (immediateRetry) {
527 _paramRequestListTimeout();
529 _paramRequestListTimer.start();
532 _paramRequestListTimer.start();
536void ParameterManager::_ftpDownloadProgress(
float progress)
538 qCDebug(ParameterManagerVerbose1Log) <<
"ParameterManager::_ftpDownloadProgress:" << progress;
539 _setLoadProgress(
static_cast<double>(progress));
540 if (progress > 0.001) {
541 _paramRequestListTimer.stop();
552 if (sharedLink->linkConfiguration()->isHighLatency() || _logReplay) {
554 _parametersReady =
true;
555 _missingParameters =
true;
556 _initialLoadComplete =
true;
557 _waitingForDefaultComponent =
false;
562 if (_tryftp && ((componentId == MAV_COMP_ID_ALL) || (componentId == MAV_COMP_ID_AUTOPILOT1))) {
563 if (!_initialLoadComplete) {
564 _paramRequestListTimer.start();
568 _waitingParamTimeoutTimer.stop();
569 if (ftpManager->
download(MAV_COMP_ID_AUTOPILOT1,
570 QStringLiteral(
"@PARAM/param.pck"),
571 QStandardPaths::writableLocation(QStandardPaths::TempLocation),
576 qCWarning(ParameterManagerLog) <<
"ParameterManager::refreshallParameters FTPManager::download returned failure";
579 }
else if (_vehicle->
px4Firmware() && !_initialLoadComplete && !_hashCheckDone) {
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)
586 _requestHashCheck(hashCheckCompId);
588 if (!_initialLoadComplete) {
589 _paramRequestListTimer.start();
593 for (
int cid: _paramCountMap.keys()) {
595 if ((componentId != MAV_COMP_ID_ALL) && (componentId != cid)) {
598 for (
int waitingIndex = 0; waitingIndex < _paramCountMap[cid]; waitingIndex++) {
600 _waitingReadParamIndexMap[cid][waitingIndex] = 0;
607 sharedLink->mavlinkChannel(),
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;
618int ParameterManager::_actualComponentId(
int componentId)
const
623 qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Default component id not set";
632 componentId = _actualComponentId(componentId);
634 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"refreshParameter - name:" << paramName <<
")";
636 _mavlinkParamRequestRead(componentId, paramName, -1,
true );
641 componentId = _actualComponentId(componentId);
642 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"refreshParametersPrefix - name:" << namePrefix <<
")";
644 for (
const QString ¶mName: _mapCompId2FactMap[componentId].keys()) {
645 if (paramName.startsWith(namePrefix)) {
655 componentId = _actualComponentId(componentId);
656 if (_mapCompId2FactMap.contains(componentId)) {
657 ret = _mapCompId2FactMap[componentId].contains(_remapParamNameToVersion(paramName));
665 componentId = _actualComponentId(componentId);
667 const QString mappedParamName = _remapParamNameToVersion(paramName);
668 if (!_mapCompId2FactMap.contains(componentId) || !_mapCompId2FactMap[componentId].contains(mappedParamName)) {
669 qgcApp()->reportMissingParameter(componentId, mappedParamName);
670 return &_defaultFact;
673 return _mapCompId2FactMap[componentId][mappedParamName];
680 const int compId = _actualComponentId(componentId);
681 const QMap<QString, Fact*> &factMap = _mapCompId2FactMap[compId];
682 for (
const QString ¶mName: factMap.keys()) {
689bool ParameterManager::_fillIndexBatchQueue(
bool waitingParamTimeout)
691 if (!_indexBatchQueueActive) {
695 constexpr int maxBatchSize = 10;
697 if (waitingParamTimeout) {
699 qCDebug(ParameterManagerLog) <<
"Refilling index based batch queue due to timeout";
700 _indexBatchQueue.clear();
702 qCDebug(ParameterManagerLog) <<
"Refilling index based batch queue due to received parameter";
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];
711 for (
const int paramIndex: _waitingReadParamIndexMap[componentId].keys()) {
712 if (_indexBatchQueue.contains(paramIndex)) {
717 if (_indexBatchQueue.count() > maxBatchSize) {
721 _waitingReadParamIndexMap[componentId][paramIndex]++;
722 if (_disableAllRetries || (_waitingReadParamIndexMap[componentId][paramIndex] > _maxInitialLoadRetrySingleParam)) {
724 _failedReadParamIndexMap[componentId] << paramIndex;
725 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"Giving up on (paramIndex:" << paramIndex <<
"retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] <<
")";
726 (void) _waitingReadParamIndexMap[componentId].remove(paramIndex);
729 _indexBatchQueue.append(paramIndex);
730 _mavlinkParamRequestRead(componentId, QString(), paramIndex,
false );
731 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"Read re-request for (paramIndex:" << paramIndex <<
"retryCount:" << _waitingReadParamIndexMap[componentId][paramIndex] <<
")";
736 return (!_indexBatchQueue.isEmpty());
739void ParameterManager::_waitingParamTimeout()
745 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"_waitingParamTimeout";
748 _indexBatchQueueActive =
true;
751 bool paramsRequested = _fillIndexBatchQueue(
true );
752 if (!paramsRequested && !_waitingForDefaultComponent && !_mapCompId2FactMap.contains(_vehicle->
defaultComponentId())) {
755 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->
defaultComponentId();
756 _waitingParamTimeoutTimer.start();
757 _waitingForDefaultComponent =
true;
760 _waitingForDefaultComponent =
false;
762 _checkInitialLoadComplete();
764 if (paramsRequested) {
765 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Restarting _waitingParamTimeoutTimer - re-request";
766 _waitingParamTimeoutTimer.start();
770void ParameterManager::_requestHashCheck(uint8_t componentId)
777 qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) <<
"Sending PARAM_REQUEST_READ for _HASH_CHECK";
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);
783 (void) mavlink_msg_param_request_read_pack_chan(
786 sharedLink->mavlinkChannel(),
788 static_cast<uint8_t
>(_vehicle->
id()),
796void ParameterManager::_mavlinkParamRequestRead(
int componentId,
const QString ¶mName,
int paramIndex,
bool notifyFailure)
798 auto paramRequestReadEncoder = [
this, componentId, paramName, paramIndex](uint8_t , 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);
806 static_cast<uint8_t
>(_vehicle->
id()),
807 static_cast<uint8_t
>(componentId),
809 static_cast<int16_t
>(paramIndex));
812 auto checkForCorrectParamValue = [componentId, paramName, paramIndex](
const mavlink_message_t &message) ->
bool {
813 if (message.compid != componentId) {
817 mavlink_param_value_t param_value{};
818 mavlink_msg_param_value_decode(&message, ¶m_value);
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);
826 if (paramIndex != -1) {
828 if (param_value.param_index != paramIndex) {
833 if (parameterName != paramName) {
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);
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);
867 stateMachine->setInitialState(sendParamRequestReadState);
886 qCDebug(ParameterManagerLog) <<
"Starting state machine for PARAM_REQUEST_READ on: " << paramName << _vehicleAndComponentString(componentId);
887 stateMachine->start();
890void ParameterManager::_writeLocalParamCache(
int vehicleId,
int componentId)
892 CacheMapName2ParamTypeVal cacheMap;
894 for (
const QString ¶mName: _mapCompId2FactMap[componentId].keys()) {
895 const Fact *
const fact = _mapCompId2FactMap[componentId][paramName];
896 cacheMap[paramName] = ParamTypeVal(fact->type(), fact->rawValue());
900 if (cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
901 QDataStream ds(&cacheFile);
904 qCWarning(ParameterManagerLog) <<
"Failed to open cache file for writing" << cacheFile.fileName();
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"));
919 return parameterCacheDir().filePath(QStringLiteral(
"%1_%2.v2").arg(vehicleId).arg(componentId));
922void ParameterManager::_tryCacheHashLoad(
int vehicleId,
int componentId,
const QVariant &hashValue)
924 qCDebug(ParameterManagerLog) <<
"Attemping load from cache";
927 CacheMapName2ParamTypeVal cacheMap;
929 if (!cacheFile.exists()) {
930 qCDebug(ParameterManagerLog) <<
"No parameter cache file";
931 if (!_hashCheckDone) {
933 _hashCheckDone =
true;
939 (void) cacheFile.open(QIODevice::ReadOnly);
942 QDataStream ds(&cacheFile);
946 uint32_t crc32_value = 0;
947 for (
const QString &name: cacheMap.keys()) {
948 const ParamTypeVal ¶mTypeVal = cacheMap[name];
953 qCDebug(ParameterManagerLog) <<
"Volatile parameter" << name;
955 const void *
const vdat = paramTypeVal.second.constData();
957 crc32_value =
QGC::crc32(
reinterpret_cast<const uint8_t *
>(qPrintable(name)), name.length(), crc32_value);
963 if (crc32_value == hashValue.toUInt()) {
964 _hashCheckDone =
true;
965 _paramRequestListTimer.stop();
966 qCDebug(ParameterManagerLog) <<
"Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
968 const int count = cacheMap.count();
970 for (
const QString &name: cacheMap.keys()) {
971 const ParamTypeVal ¶mTypeVal = cacheMap[name];
974 _handleParamValue(componentId, name, count, index++, mavParamType, paramTypeVal.second);
979 mavlink_param_set_t p{};
980 mavlink_param_union_t union_value{};
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);
993 sharedLink->mavlinkChannel(),
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);
1006 (void) connect(ani, &QVariantAnimation::valueChanged,
this, [
this](
const QVariant &value) {
1007 _setLoadProgress(value.toDouble());
1011 connect(ani, &QVariantAnimation::finished,
this, [
this] {
1012 QTimer::singleShot(500,
this, [
this] {
1013 _setLoadProgress(0);
1017 ani->start(QAbstractAnimation::DeleteWhenStopped);
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;
1026 qgcApp()->showAppMessage(tr(
"Parameter cache CRC match failed"));
1028 if (!_hashCheckDone) {
1030 _hashCheckDone =
true;
1039 QString missingErrors;
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());
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();
1059 error += QStringLiteral(
"%1:%2").arg(componentId).arg(paramName);
1060 missingErrors +=
error;
1061 qCDebug(ParameterManagerLog) <<
"Skipped due to missing:" <<
error;
1068 error = QStringLiteral(
"%1:%2 ").arg(componentId).arg(paramName);
1069 typeErrors +=
error;
1070 qCDebug(ParameterManagerLog) <<
"Skipped due to type mismatch: %1" <<
error;
1074 qCDebug(ParameterManagerLog) <<
"Updating parameter" << componentId << paramName << valStr;
1075 fact->setRawValue(valStr);
1082 if (!missingErrors.isEmpty()) {
1083 errors = tr(
"Parameters not loaded since they are not currently on the vehicle: %1\n").arg(missingErrors);
1086 if (!typeErrors.isEmpty()) {
1087 errors += tr(
"Parameters not loaded due to type mismatch: %1").arg(typeErrors);
1095 stream <<
"# Onboard parameters for Vehicle " << _vehicle->
id() <<
"\n";
1100 stream <<
"# Version: "
1105 stream <<
"# Git Revision: " << _vehicle->
gitHash() <<
"\n";
1108 stream <<
"# Vehicle-Id Component-Id Name Value Type\n";
1110 for (
const int componentId: _mapCompId2FactMap.keys()) {
1111 for (
const QString ¶mName: _mapCompId2FactMap[componentId].keys()) {
1112 const Fact *
const fact = _mapCompId2FactMap[componentId][paramName];
1114 stream << _vehicle->
id() <<
"\t" << componentId <<
"\t" << paramName <<
"\t" << fact->rawValueStringFullPrecision() <<
"\t" << QStringLiteral(
"%1").arg(
factTypeToMavType(fact->type())) <<
"\n";
1116 qCWarning(ParameterManagerLog) <<
"Internal error: missing fact";
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;
1146 qCWarning(ParameterManagerLog) <<
"Unsupported fact type" << factType;
1149 return MAV_PARAM_TYPE_INT32;
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:
1175 qCWarning(ParameterManagerLog) <<
"Unsupported mav param type" << mavType;
1177 case MAV_PARAM_TYPE_INT32:
1182void ParameterManager::_checkInitialLoadComplete()
1184 if (_initialLoadComplete) {
1188 for (
const int componentId: _waitingReadParamIndexMap.keys()) {
1189 if (!_waitingReadParamIndexMap[componentId].isEmpty()) {
1201 _initialLoadComplete =
true;
1204 for (
const int componentId: _debugCacheParamSeen.keys()) {
1205 if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
1206 for (
const QString ¶mName: _debugCacheParamSeen[componentId].keys()) {
1207 if (!_debugCacheParamSeen[componentId][paramName]) {
1208 qCDebug(ParameterManagerLog) <<
"Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
1213 _debugCacheCRC.clear();
1215 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Initial load complete";
1219 bool initialLoadFailures =
false;
1220 for (
const int componentId: _failedReadParamIndexMap.keys()) {
1221 for (
const int paramIndex: _failedReadParamIndexMap[componentId]) {
1222 if (initialLoadFailures) {
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 <<
")";
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;
1246 _parametersReady =
true;
1252void ParameterManager::_hashCheckTimeout()
1254 _hashCheckDone =
true;
1255 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"_HASH_CHECK timed out, falling back to PARAM_REQUEST_LIST";
1259void ParameterManager::_paramRequestListTimeout()
1263 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"_paramRequestListTimeout (log replay): Signalling load complete";
1264 _initialLoadComplete =
true;
1265 _missingParameters =
false;
1266 _parametersReady =
true;
1273 if (!_disableAllRetries && (++_initialRequestRetryCount <= _maxInitialRequestListRetry)) {
1274 qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) <<
"Retrying initial parameter request list";
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);
1284QString ParameterManager::_remapParamNameToVersion(
const QString ¶mName)
const
1286 if (!paramName.startsWith(QStringLiteral(
"r."))) {
1294 qCDebug(ParameterManagerLog) <<
"_remapParamNameToVersion" << paramName << majorVersion << minorVersion;
1296 QString mappedParamName = paramName.right(paramName.length() - 2);
1299 return mappedParamName;
1303 if (!majorVersionRemap.contains(majorVersion)) {
1305 qCDebug(ParameterManagerLog) <<
"_remapParamNameToVersion: no major version mapping";
1306 return mappedParamName;
1312 if (remapMinorVersion.contains(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;
1322 return mappedParamName;
1325void ParameterManager::_loadOfflineEditingParams()
1328 if (paramFilename.isEmpty()) {
1332 QFile paramFile(paramFilename);
1333 if (!paramFile.open(QFile::ReadOnly)) {
1334 qCWarning(ParameterManagerLog) <<
"Unable to open offline editing params file" << paramFilename;
1337 QTextStream paramStream(¶mFile);
1338 while (!paramStream.atEnd()) {
1339 const QString line = paramStream.readLine();
1340 if (line.startsWith(
"#")) {
1344 const QStringList paramData = line.split(
"\t");
1345 Q_ASSERT(paramData.count() == 5);
1347 const int offlineDefaultComponentId = paramData.at(1).toInt();
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());
1353 QVariant paramValue;
1354 switch (paramType) {
1355 case MAV_PARAM_TYPE_REAL32:
1356 paramValue = QVariant(valStr.toFloat());
1358 case MAV_PARAM_TYPE_UINT32:
1359 paramValue = QVariant(valStr.toUInt());
1361 case MAV_PARAM_TYPE_UINT16:
1362 paramValue = QVariant((quint16)valStr.toUInt());
1364 case MAV_PARAM_TYPE_INT16:
1365 paramValue = QVariant((qint16)valStr.toInt());
1367 case MAV_PARAM_TYPE_UINT8:
1368 paramValue = QVariant((quint8)valStr.toUInt());
1370 case MAV_PARAM_TYPE_INT8:
1371 paramValue = QVariant((qint8)valStr.toUInt());
1374 qCCritical(ParameterManagerLog) <<
"Unknown type" << paramType;
1376 case MAV_PARAM_TYPE_INT32:
1377 paramValue = QVariant(valStr.toInt());
1384 fact->setMetaData(factMetaData);
1389 _parametersReady =
true;
1390 _initialLoadComplete =
true;
1391 _debugCacheCRC.clear();
1397 MAV_CMD_PREFLIGHT_STORAGE,
1407 if (sysAutoConfigFact) {
1408 sysAutoConfigFact->setRawValue(2);
1412QString ParameterManager::_logVehiclePrefix(
int componentId)
const
1414 if (componentId == -1) {
1415 return QStringLiteral(
"V:%1").arg(_vehicle->
id());
1417 return QStringLiteral(
"V:%1 C:%2").arg(_vehicle->
id()).arg(componentId);
1421void ParameterManager::_setLoadProgress(
double loadProgress)
1431 return _paramCountMap.keys();
1436 return _pendingWritesCount > 0;
1445bool ParameterManager::_parseParamFile(
const QString& filename)
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;
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.";
1468 QDataStream in(&file);
1469 in.setByteOrder(QDataStream::LittleEndian);
1471 quint16 magic, num_params, total_params;
1476 if (in.status() != QDataStream::Ok) {
1477 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: Could not read Header";
1481 qCDebug(ParameterManagerVerbose2Log) <<
"_parseParamFile: magic: 0x" << Qt::hex << magic;
1482 qCDebug(ParameterManagerVerbose2Log) <<
"_parseParamFile: num_params:" << num_params
1483 <<
"total_params:" << total_params;
1485 if ((magic != magic_standard) && (magic != magic_withdefaults)) {
1486 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: File does not start with Magic";
1489 if (num_params > total_params) {
1490 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: total_params > num_params";
1493 if (num_params != total_params) {
1495 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: total_params != num_params";
1499 while (in.status() == QDataStream::Ok) {
1503 quint8 name_len = 0;
1504 quint8 common_len = 0;
1505 bool withdefault =
false;
1507 char name_buffer[17];
1509 while (
byte == 0x0) {
1511 if (in.status() != QDataStream::Ok) {
1512 if (no_of_parameters_found == num_params) {
1515 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: unexpected EOF"
1516 <<
"number of parameters expected:" << num_params
1517 <<
"actual:" << no_of_parameters_found;
1522 ptype =
byte & 0x0F;
1523 flags = (
byte >> 4) & 0x0F;
1524 withdefault = (flags & 0x01) == 0x01;
1526 if (in.status() != QDataStream::Ok) {
1527 qCritical(ParameterManagerLog) <<
"_parseParamFile: Error: Unexpected EOF while reading flags";
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;
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;
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
1551 <<
"flags" << flags;
1553 QVariant parameterValue = 0;
1554 switch (
static_cast<ap_var_type
>(ptype)) {
1561 parameterValue = data8;
1566 case AP_PARAM_INT16:
1568 parameterValue = data16;
1573 case AP_PARAM_INT32:
1575 parameterValue = data32;
1580 case AP_PARAM_FLOAT:
1582 (void) memcpy(&dfloat, &data32, 4);
1583 parameterValue = dfloat;
1589 qCDebug(ParameterManagerLog) <<
"_parseParamFile: Error: type is out of range" << ptype;
1593 qCDebug(ParameterManagerVerbose2Log) <<
"paramValue" << parameterValue;
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;
1603 (ptype == AP_PARAM_INT16) ?
FactMetaData::valueTypeInt16 :
1604 (ptype == AP_PARAM_INT32) ?
FactMetaData::valueTypeInt32 :
1607 Fact *fact =
nullptr;
1608 if (_mapCompId2FactMap.contains(componentId) && _mapCompId2FactMap[componentId].contains(parameterName)) {
1609 fact = _mapCompId2FactMap[componentId][parameterName];
1611 qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) <<
"Adding new fact" << parameterName;
1613 fact =
new Fact(componentId, parameterName, factType,
this);
1615 fact->setMetaData(factMetaData);
1617 _mapCompId2FactMap[componentId][parameterName] = fact;
1624 fact->containerSetRawValue(parameterValue);
1630 _paramCountMap[componentId] = num_params;
1631 _totalParamCount += num_params;
1632 _waitingReadParamIndexMap[componentId] = QMap<int, int>();
1633 _checkInitialLoadComplete();
1634 _setLoadProgress(0.0);
1642void ParameterManager::_incrementPendingWriteCount()
1644 _pendingWritesCount++;
1645 if (_pendingWritesCount == 1) {
1650void ParameterManager::_decrementPendingWriteCount()
1652 if (_pendingWritesCount == 0) {
1653 qCWarning(ParameterManagerLog) <<
"Internal Error: _pendingWriteCount == 0";
1657 _pendingWritesCount--;
1658 if (_pendingWritesCount == 0) {
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
FactMetaData * factMetaDataForName(const QString &name, FactMetaData::ValueType_t valueType)
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)
A Fact is used to hold a single value within the system.
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 ¶mName) 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 ¶mName)
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 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)
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.
void resetAllToVehicleConfiguration()
static QString parameterCacheFile(int vehicleId, int componentId)
void writeParametersToStream(QTextStream &stream) const
void _paramSetFailure(int componentId, const QString ¶mName)
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.
Sends the specified MAVLink message to the vehicle.
Display an application message to the user.
WeakLinkInterfacePtr primaryLink() const
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)
static const int versionNotSetValue
QString firmwareVersionTypeString() const
VehicleLinkManager * vehicleLinkManager()
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
ComponentInformationManager * compInfoManager()
int firmwareMinorVersion() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
bool genericFirmware() const
AutoPilotPlugin * autopilotPlugin()
Provides access to AutoPilotPlugin for this vehicle.
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
int firmwarePatchVersion() const
QString firmwareTypeString() const
FTPManager * ftpManager()
int firmwareMajorVersion() const
QString vehicleTypeString() const
Error
Error codes for decompression operations.
quint32 crc32(const quint8 *src, unsigned len, unsigned state)
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.