QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RequestMetaDataTypeStateMachine.cc
Go to the documentation of this file.
5#include "Vehicle.h"
6#include "FTPManager.h"
7#include "QGCCompression.h"
8#include "CompInfoGeneral.h"
9#include "QGCApplication.h"
11#include "QGCLoggingCategory.h"
12
13// State types included via QGCStateMachine.h in header
14
15#include <QtCore/QCoreApplication>
16#include <QtCore/QStandardPaths>
17#include <QtCore/QDir>
18#include <QtCore/QFile>
19
20QGC_LOGGING_CATEGORY(RequestMetaDataTypeStateMachineLog, "ComponentInformation.RequestMetaDataTypeStateMachine")
21
23 : QGCStateMachine("RequestMetaDataType", compMgr->vehicle(), parent)
24 , _compMgr(compMgr)
25{
26 qCDebug(RequestMetaDataTypeStateMachineLog) << Q_FUNC_INFO << this;
27
28 _createStates();
29 _wireTransitions();
30 _wireTimeoutHandling();
31}
32
34{
35 qCDebug(RequestMetaDataTypeStateMachineLog) << this;
36}
37
38void RequestMetaDataTypeStateMachine::_createStates()
39{
40 // State 1: Request COMPONENT_METADATA message
41 _stateRequestCompInfo = new AsyncFunctionState(
42 "RequestCompMetadata",
43 this,
44 [this](AsyncFunctionState*) { _requestCompInfo(); },
45 _timeoutCompInfoRequest
46 );
47 registerState(_stateRequestCompInfo);
48
49 // State 2: Fallback to deprecated COMPONENT_INFORMATION if needed
50 _stateRequestDeprecated = new SkippableAsyncState(
51 "RequestCompInfoDeprecated",
52 this,
53 [this]() { return _shouldSkipDeprecatedRequest(); },
54 [this](SkippableAsyncState*) { _requestCompInfoDeprecated(); },
55 nullptr,
56 _timeoutCompInfoRequest
57 );
58 registerState(_stateRequestDeprecated);
59
60 // State 3: Download metadata JSON
61 _stateRequestMetaDataJson = new AsyncFunctionState(
62 "RequestMetaDataJson",
63 this,
64 [this](AsyncFunctionState*) { _requestMetaDataJson(); },
65 _timeoutMetaDataDownload
66 );
67 registerState(_stateRequestMetaDataJson);
68
69 // State 4: Try fallback URI if primary download failed
70 _stateRequestMetaDataJsonFallback = new SkippableAsyncState(
71 "RequestMetaDataJsonFallback",
72 this,
73 [this]() { return _shouldSkipFallback(); },
74 [this](SkippableAsyncState*) { _requestMetaDataJsonFallback(); },
75 nullptr,
76 _timeoutMetaDataDownload
77 );
78 registerState(_stateRequestMetaDataJsonFallback);
79
80 // State 5: Download translation JSON
81 _stateRequestTranslationJson = new AsyncFunctionState(
82 "RequestTranslationJson",
83 this,
84 [this](AsyncFunctionState*) { _requestTranslationJson(); },
85 _timeoutMetaDataDownload
86 );
87 registerState(_stateRequestTranslationJson);
88
89 // State 6: Translate metadata
90 _stateRequestTranslate = new SkippableAsyncState(
91 "RequestTranslate",
92 this,
93 [this]() { return _shouldSkipTranslation(); },
94 [this](SkippableAsyncState*) { _requestTranslate(); },
95 nullptr,
96 _timeoutTranslation
97 );
98 registerState(_stateRequestTranslate);
99
100 // State 7: Complete request
101 // Use ErrorRecoveryState shape (without retries/fallback) so completion
102 // stays in the unified recovery framework used by this utility.
103 _stateComplete = addErrorRecoveryState(
104 "CompleteRequest",
105 [this]() {
106 _completeRequest();
107 return true;
108 },
109 0,
110 0,
112 );
113
114 _stateFinal = addFinalState("Final");
115
116 setInitialState(_stateRequestCompInfo);
117}
118
119void RequestMetaDataTypeStateMachine::_wireTransitions()
120{
121 // Use completed() for WaitStateBase-derived states (more semantic than advance())
122
123 // RequestCompMetadata -> RequestDeprecated
124 _stateRequestCompInfo->addTransition(_stateRequestCompInfo, &WaitStateBase::completed, _stateRequestDeprecated);
125
126 // RequestDeprecated -> RequestMetaDataJson (either via completed or skipped)
127 _stateRequestDeprecated->addTransition(_stateRequestDeprecated, &WaitStateBase::completed, _stateRequestMetaDataJson);
128 _stateRequestDeprecated->addTransition(_stateRequestDeprecated, &SkippableAsyncState::skipped, _stateRequestMetaDataJson);
129
130 // RequestMetaDataJson -> RequestMetaDataJsonFallback
131 _stateRequestMetaDataJson->addTransition(_stateRequestMetaDataJson, &WaitStateBase::completed, _stateRequestMetaDataJsonFallback);
132
133 // RequestMetaDataJsonFallback -> RequestTranslationJson
134 _stateRequestMetaDataJsonFallback->addTransition(_stateRequestMetaDataJsonFallback, &WaitStateBase::completed, _stateRequestTranslationJson);
135 _stateRequestMetaDataJsonFallback->addTransition(_stateRequestMetaDataJsonFallback, &SkippableAsyncState::skipped, _stateRequestTranslationJson);
136
137 // RequestTranslationJson -> RequestTranslate
138 _stateRequestTranslationJson->addTransition(_stateRequestTranslationJson, &WaitStateBase::completed, _stateRequestTranslate);
139
140 // RequestTranslate -> CompleteRequest
141 _stateRequestTranslate->addTransition(_stateRequestTranslate, &WaitStateBase::completed, _stateComplete);
142 _stateRequestTranslate->addTransition(_stateRequestTranslate, &SkippableAsyncState::skipped, _stateComplete);
143
144 // CompleteRequest -> Final (QGCState advance())
145 _stateComplete->addTransition(_stateComplete, &QGCState::advance, _stateFinal);
146
147 // Emit requestComplete when machine finishes (reaches final state and stops)
148 connect(this, &QStateMachine::finished, this, &RequestMetaDataTypeStateMachine::requestComplete);
149}
150
151void RequestMetaDataTypeStateMachine::_wireTimeoutHandling()
152{
153 // On timeout, gracefully advance to next state (don't block the connection sequence)
154 // Timeout indicates the operation failed, but we continue with degraded functionality
155
156 _stateRequestCompInfo->addTransition(_stateRequestCompInfo, &WaitStateBase::timedOut, _stateRequestDeprecated);
157
158 _stateRequestDeprecated->addTransition(_stateRequestDeprecated, &WaitStateBase::timedOut, _stateRequestMetaDataJson);
159
160 _stateRequestMetaDataJson->addTransition(_stateRequestMetaDataJson, &WaitStateBase::timedOut, _stateRequestMetaDataJsonFallback);
161
162 _stateRequestMetaDataJsonFallback->addTransition(_stateRequestMetaDataJsonFallback, &WaitStateBase::timedOut, _stateRequestTranslationJson);
163
164 _stateRequestTranslationJson->addTransition(_stateRequestTranslationJson, &WaitStateBase::timedOut, _stateRequestTranslate);
165
166 _stateRequestTranslate->addTransition(_stateRequestTranslate, &WaitStateBase::timedOut, _stateComplete);
167}
168
170{
171 _compInfo = compInfo;
172 qCDebug(RequestMetaDataTypeStateMachineLog) << Q_FUNC_INFO << typeToString();
173
174 _jsonMetadataFileName.clear();
175 _jsonMetadataTranslatedFileName.clear();
176 _jsonTranslationFileName.clear();
177 _activeAsyncState = nullptr;
178 _activeSkippableState = nullptr;
179 _metadataSource = MetadataSource::None;
180 _metadataUri.clear();
181 _metadataIsFallback = false;
182
183 start();
184}
185
187{
188 if (!_compInfo) return "Unknown";
189
190 switch (_compInfo->type) {
191 case COMP_METADATA_TYPE_GENERAL: return "COMP_METADATA_TYPE_GENERAL";
192 case COMP_METADATA_TYPE_PARAMETER: return "COMP_METADATA_TYPE_PARAMETER";
193 case COMP_METADATA_TYPE_COMMANDS: return "COMP_METADATA_TYPE_COMMANDS";
194 case COMP_METADATA_TYPE_PERIPHERALS: return "COMP_METADATA_TYPE_PERIPHERALS";
195 case COMP_METADATA_TYPE_EVENTS: return "COMP_METADATA_TYPE_EVENTS";
196 case COMP_METADATA_TYPE_ACTUATORS: return "COMP_METADATA_TYPE_ACTUATORS";
197 default: return "Unknown";
198 }
199}
200
201bool RequestMetaDataTypeStateMachine::_shouldSkipCompInfoRequest() const
202{
203 return _compInfo->type != COMP_METADATA_TYPE_GENERAL;
204}
205
206bool RequestMetaDataTypeStateMachine::_shouldSkipDeprecatedRequest() const
207{
208 // Skip if not GENERAL type
209 if (_compInfo->type != COMP_METADATA_TYPE_GENERAL) {
210 return true;
211 }
212 // Skip if we already got valid CRC from COMPONENT_METADATA
213 if (_compInfo->crcMetaDataValid()) {
214 qCDebug(RequestMetaDataTypeStateMachineLog) << "COMPONENT_METADATA available, skipping COMPONENT_INFORMATION";
215 return true;
216 }
217 return false;
218}
219
220bool RequestMetaDataTypeStateMachine::_shouldSkipFallback() const
221{
222 // Skip fallback if primary download succeeded
223 return !_jsonMetadataFileName.isEmpty();
224}
225
226bool RequestMetaDataTypeStateMachine::_shouldSkipTranslation() const
227{
228 // Skip if no translation file was downloaded
229 return _jsonTranslationFileName.isEmpty();
230}
231
232void RequestMetaDataTypeStateMachine::_requestCompInfo()
233{
234 if (_shouldSkipCompInfoRequest()) {
235 _stateRequestCompInfo->complete();
236 return;
237 }
238
239 Vehicle* vehicle = _compMgr->vehicle();
240 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
241
242 if (!sharedLink) {
243 qCDebug(RequestMetaDataTypeStateMachineLog) << "Skipping component information request due to no primary link" << typeToString();
244 _stateRequestCompInfo->complete();
245 return;
246 }
247
248 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
249 qCDebug(RequestMetaDataTypeStateMachineLog) << "Skipping component information request due to link type" << typeToString();
250 _stateRequestCompInfo->complete();
251 return;
252 }
253
254 qCDebug(RequestMetaDataTypeStateMachineLog) << "Requesting component metadata" << typeToString();
255
256 vehicle->requestMessage(
257 [](void* resultHandlerData, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t, const mavlink_message_t& message) {
258 auto* self = static_cast<RequestMetaDataTypeStateMachine*>(resultHandlerData);
259 self->_handleCompMetadataResult(result, message);
260 },
261 this,
262 MAV_COMP_ID_AUTOPILOT1,
263 MAVLINK_MSG_ID_COMPONENT_METADATA
264 );
265}
266
267void RequestMetaDataTypeStateMachine::_handleCompMetadataResult(MAV_RESULT result, const mavlink_message_t& message)
268{
269 if (result == MAV_RESULT_ACCEPTED) {
270 mavlink_component_metadata_t componentMetadata;
271 mavlink_msg_component_metadata_decode(&message, &componentMetadata);
272 _compInfo->setUriMetaData(componentMetadata.uri, componentMetadata.file_crc);
273 }
274 // else: try deprecated COMPONENT_INFORMATION in next state
275
276 _stateRequestCompInfo->complete();
277}
278
279void RequestMetaDataTypeStateMachine::_requestCompInfoDeprecated()
280{
281 Vehicle* vehicle = _compMgr->vehicle();
282 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
283
284 if (!sharedLink) {
285 qCDebug(RequestMetaDataTypeStateMachineLog) << "Skipping deprecated component information request due to no primary link" << typeToString();
286 _stateRequestDeprecated->complete();
287 return;
288 }
289
290 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
291 qCDebug(RequestMetaDataTypeStateMachineLog) << "Skipping deprecated component information request due to link type" << typeToString();
292 _stateRequestDeprecated->complete();
293 return;
294 }
295
296 qCDebug(RequestMetaDataTypeStateMachineLog) << "Requesting component information (deprecated)" << typeToString();
297
298 vehicle->requestMessage(
299 [](void* resultHandlerData, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message) {
300 auto* self = static_cast<RequestMetaDataTypeStateMachine*>(resultHandlerData);
301 self->_handleCompInfoResult(result, failureCode, message);
302 },
303 this,
304 MAV_COMP_ID_AUTOPILOT1,
305 MAVLINK_MSG_ID_COMPONENT_INFORMATION
306 );
307}
308
309void RequestMetaDataTypeStateMachine::_handleCompInfoResult(MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message)
310{
311 if (result == MAV_RESULT_ACCEPTED) {
312 mavlink_component_information_t componentInformation;
313 mavlink_msg_component_information_decode(&message, &componentInformation);
314 _compInfo->setUriMetaData(componentInformation.general_metadata_uri, componentInformation.general_metadata_file_crc);
315 } else {
316 switch (failureCode) {
318 qCDebug(RequestMetaDataTypeStateMachineLog) << "MAV_CMD_REQUEST_MESSAGE COMPONENT_INFORMATION error:" << QGCMAVLink::mavResultToString(result) << typeToString();
319 break;
321 qCDebug(RequestMetaDataTypeStateMachineLog) << "MAV_CMD_REQUEST_MESSAGE COMPONENT_INFORMATION no response from vehicle" << typeToString();
322 break;
324 qCDebug(RequestMetaDataTypeStateMachineLog) << "MAV_CMD_REQUEST_MESSAGE COMPONENT_INFORMATION message not received" << typeToString();
325 break;
326 default:
327 break;
328 }
329 }
330
331 _stateRequestDeprecated->complete();
332}
333
334void RequestMetaDataTypeStateMachine::_requestMetaDataJson()
335{
336 CompInfo* compInfo = _compInfo;
337 const QString fileTag = ComponentInformationManager::_getFileCacheTag(compInfo->type, compInfo->crcMetaData(), false);
338 const QString uri = compInfo->uriMetaData();
339 _jsonMetadataCrcValid = compInfo->crcMetaDataValid();
340
341 qCDebug(ComponentInformationManagerLog) << typeToString() << ": requesting metadata (primary) from" << uri;
342
343 _activeAsyncState = _stateRequestMetaDataJson;
344 _activeSkippableState = nullptr;
345 _requestFile(fileTag, compInfo->crcMetaDataValid(), uri, _jsonMetadataFileName, true);
346}
347
348void RequestMetaDataTypeStateMachine::_requestMetaDataJsonFallback()
349{
350 qCDebug(ComponentInformationManagerLog) << typeToString() << ": primary failed, requesting metadata (fallback) from" << _compInfo->uriMetaDataFallback();
351 _metadataIsFallback = true;
352
353 CompInfo* compInfo = _compInfo;
354 const QString fileTag = ComponentInformationManager::_getFileCacheTag(compInfo->type, compInfo->crcMetaDataFallback(), false);
355 const QString uri = compInfo->uriMetaDataFallback();
356 _jsonMetadataCrcValid = compInfo->crcMetaDataFallbackValid();
357
358 _activeAsyncState = nullptr;
359 _activeSkippableState = _stateRequestMetaDataJsonFallback;
360 _requestFile(fileTag, compInfo->crcMetaDataFallbackValid(), uri, _jsonMetadataFileName, true);
361}
362
363void RequestMetaDataTypeStateMachine::_requestTranslationJson()
364{
365 CompInfo* compInfo = _compInfo;
366 const QString uri = compInfo->uriTranslation();
367
368 if (uri.isEmpty()) {
369 qCDebug(RequestMetaDataTypeStateMachineLog) << "No translation URI for" << typeToString();
370 _stateRequestTranslationJson->complete();
371 return;
372 }
373
374 _activeAsyncState = _stateRequestTranslationJson;
375 _activeSkippableState = nullptr;
376 _requestFile("", false, uri, _jsonTranslationFileName, false);
377}
378
379void RequestMetaDataTypeStateMachine::_requestTranslate()
380{
382 this, &RequestMetaDataTypeStateMachine::_downloadAndTranslationComplete);
383
384 if (!_compMgr->translation()->downloadAndTranslate(_jsonTranslationFileName,
385 _jsonMetadataFileName,
387 typeToString())) {
389 this, &RequestMetaDataTypeStateMachine::_downloadAndTranslationComplete);
390 qCDebug(RequestMetaDataTypeStateMachineLog) << "downloadAndTranslate() failed";
391 _stateRequestTranslate->complete();
392 }
393}
394
395void RequestMetaDataTypeStateMachine::_downloadAndTranslationComplete(QString translatedJsonTempFile, QString errorMsg)
396{
398 this, &RequestMetaDataTypeStateMachine::_downloadAndTranslationComplete);
399
400 _jsonMetadataTranslatedFileName = translatedJsonTempFile;
401 if (!errorMsg.isEmpty()) {
402 qCWarning(RequestMetaDataTypeStateMachineLog) << "Metadata translation failed:" << errorMsg;
403 }
404
405 _stateRequestTranslate->complete();
406}
407
408void RequestMetaDataTypeStateMachine::_completeRequest()
409{
410 const bool success = !_jsonMetadataFileName.isEmpty();
411 const bool translated = !_jsonMetadataTranslatedFileName.isEmpty();
412
413 if (translated) {
414 _compInfo->setJson(_jsonMetadataTranslatedFileName);
415 QFile(_jsonMetadataTranslatedFileName).remove();
416 } else {
417 _compInfo->setJson(_jsonMetadataFileName);
418 }
419
420 // If we don't have a CRC we didn't cache the file and need to delete it
421 if (!_jsonMetadataCrcValid && !_jsonMetadataFileName.isEmpty()) {
422 QFile(_jsonMetadataFileName).remove();
423 }
424 if (!_jsonMetadataCrcValid && !_jsonTranslationFileName.isEmpty()) {
425 QFile(_jsonTranslationFileName).remove();
426 }
427
428 // Summary log for easy filtering
429 const char* sourceLabel = _metadataIsFallback ? "(fallback)" : "(primary)";
430 if (success) {
431 if (translated) {
432 qCDebug(ComponentInformationManagerLog) << typeToString() << ":" << _metadataSourceToString(_metadataSource)
433 << sourceLabel << "(translated)" << _metadataUri;
434 } else {
435 qCDebug(ComponentInformationManagerLog) << typeToString() << ":" << _metadataSourceToString(_metadataSource)
436 << sourceLabel << _metadataUri;
437 }
438 } else {
439 qCWarning(ComponentInformationManagerLog) << typeToString() << ": failed to load metadata (primary and fallback)"
440 << (_metadataUri.isEmpty() ? _compInfo->uriMetaData() : _metadataUri);
441 }
442}
443
444const char* RequestMetaDataTypeStateMachine::_metadataSourceToString(MetadataSource source)
445{
446 switch (source) {
447 case MetadataSource::Cache: return "loaded from cache";
448 case MetadataSource::FTP: return "downloaded via FTP";
449 case MetadataSource::HTTP: return "downloaded via HTTP";
450 case MetadataSource::None: return "not available";
451 }
452 return "unknown";
453}
454
455void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag, bool crcValid, const QString& uri, QString& outputFileName, bool trackMetadataSource)
456{
457 FTPManager* ftpManager = _compInfo->vehicle->ftpManager();
458 _currentCacheFileTag = cacheFileTag;
459 _currentFileName = &outputFileName;
460 _currentFileValidCrc = crcValid;
461 outputFileName.clear();
462
463 auto completeCurrentState = [this]() {
464 if (_activeAsyncState) {
465 _activeAsyncState->complete();
466 } else if (_activeSkippableState) {
467 _activeSkippableState->complete();
468 }
469 };
470
471 if (!_compInfo->available() || uri.isEmpty()) {
472 qCDebug(ComponentInformationManagerLog) << typeToString() << ": metadata not available, skipping download";
473 completeCurrentState();
474 return;
475 }
476
477 const QString cachedFile = crcValid ? _compMgr->fileCache().access(cacheFileTag) : "";
478
479 if (!cachedFile.isEmpty()) {
480 qCDebug(RequestMetaDataTypeStateMachineLog) << "Using cached file" << cachedFile;
481 if (trackMetadataSource) {
482 _metadataSource = MetadataSource::Cache;
483 _metadataUri = uri;
484 }
485 outputFileName = cachedFile;
486 completeCurrentState();
487 return;
488 }
489
490 if (!crcValid) {
491 qCDebug(RequestMetaDataTypeStateMachineLog) << typeToString() << ": CRC not available, cache bypassed";
492 } else {
493 qCDebug(RequestMetaDataTypeStateMachineLog) << typeToString() << ": not found in cache, downloading";
494 }
495
496 qCDebug(RequestMetaDataTypeStateMachineLog) << "Downloading json" << uri;
497
498 if (_uriIsMAVLinkFTP(uri)) {
499 if (trackMetadataSource) {
500 _metadataSource = MetadataSource::FTP;
501 _metadataUri = uri;
502 }
503 connect(ftpManager, &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
504 if (ftpManager->download(MAV_COMP_ID_AUTOPILOT1, uri, QStandardPaths::writableLocation(QStandardPaths::TempLocation))) {
505 _downloadStartTime.start();
506 connect(ftpManager, &FTPManager::commandProgress, this, &RequestMetaDataTypeStateMachine::_ftpDownloadProgress);
507 } else {
508 qCWarning(RequestMetaDataTypeStateMachineLog) << "FTPManager::download returned failure";
509 disconnect(ftpManager, &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
510 completeCurrentState();
511 }
512 } else {
513 if (trackMetadataSource) {
514 _metadataSource = MetadataSource::HTTP;
515 _metadataUri = uri;
516 }
517 connect(_compMgr->_cachedFileDownload, &QGCCachedFileDownload::finished,
518 this, &RequestMetaDataTypeStateMachine::_httpDownloadComplete);
519 if (_compMgr->_cachedFileDownload->download(uri, crcValid ? 0 : ComponentInformationManager::cachedFileMaxAgeSec)) {
520 _downloadStartTime.start();
521 } else {
522 qCWarning(RequestMetaDataTypeStateMachineLog) << "QGCCachedFileDownload::download returned failure";
523 disconnect(_compMgr->_cachedFileDownload, &QGCCachedFileDownload::finished,
524 this, &RequestMetaDataTypeStateMachine::_httpDownloadComplete);
525 completeCurrentState();
526 }
527 }
528}
529
530QString RequestMetaDataTypeStateMachine::_downloadCompleteJsonWorker(const QString& fileName)
531{
532 const QString tempPath = QDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)).absoluteFilePath(_currentCacheFileTag);
533 QString outputFileName = QGCCompression::decompressIfNeeded(fileName, tempPath);
534 if (outputFileName.isEmpty()) {
535 qCWarning(RequestMetaDataTypeStateMachineLog) << "Inflate of compressed json failed" << _currentCacheFileTag;
536 }
537
538 if (_currentFileValidCrc) {
539 // Cache the file (this will move/remove the temp file as well)
540 outputFileName = _compMgr->fileCache().insert(_currentCacheFileTag, outputFileName);
541 }
542 return outputFileName;
543}
544
545void RequestMetaDataTypeStateMachine::_ftpDownloadComplete(const QString& fileName, const QString& errorMsg)
546{
547 qCDebug(RequestMetaDataTypeStateMachineLog) << "_ftpDownloadComplete fileName:errorMsg" << fileName << errorMsg;
548
549 disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
550 disconnect(_compInfo->vehicle->ftpManager(), &FTPManager::commandProgress, this, &RequestMetaDataTypeStateMachine::_ftpDownloadProgress);
551
552 if (errorMsg.isEmpty()) {
553 if (_currentFileName) {
554 *_currentFileName = _downloadCompleteJsonWorker(fileName);
555 }
556 } else {
557 qCDebug(ComponentInformationManagerLog) << typeToString() << ": FTP download failed:" << errorMsg;
558 }
559
560 if (_activeAsyncState) {
561 _activeAsyncState->complete();
562 } else if (_activeSkippableState) {
563 _activeSkippableState->complete();
564 }
565}
566
567void RequestMetaDataTypeStateMachine::_ftpDownloadProgress(float progress)
568{
569 int elapsedSec = _downloadStartTime.elapsed() / 1000;
570 float totalDownloadTime = elapsedSec / progress;
571
572 // Abort download if it's too slow (e.g. over telemetry link) and use the fallback
573 const int maxDownloadTimeSec = 40;
574 if (elapsedSec > 10 && progress < 0.5 && totalDownloadTime > maxDownloadTimeSec) {
575 qCDebug(RequestMetaDataTypeStateMachineLog) << "Slow download, aborting. Total time (s):" << totalDownloadTime;
576 _compInfo->vehicle->ftpManager()->cancelDownload();
577 }
578}
579
580void RequestMetaDataTypeStateMachine::_httpDownloadComplete(bool success, const QString& localFile, const QString& errorMsg, bool fromCache)
581{
582 qCDebug(RequestMetaDataTypeStateMachineLog) << "_httpDownloadComplete success:localFile:errorMsg:fromCache"
583 << success << localFile << errorMsg << fromCache;
584
585 disconnect(_compMgr->_cachedFileDownload, &QGCCachedFileDownload::finished,
586 this, &RequestMetaDataTypeStateMachine::_httpDownloadComplete);
587
588 if (success && errorMsg.isEmpty()) {
589 if (_currentFileName) {
590 *_currentFileName = _downloadCompleteJsonWorker(localFile);
591 }
592 } else {
593 qCDebug(ComponentInformationManagerLog) << typeToString() << ": HTTP download failed:" << errorMsg;
594 }
595
596 if (_activeAsyncState) {
597 _activeAsyncState->complete();
598 } else if (_activeSkippableState) {
599 _activeSkippableState->complete();
600 }
601}
602
603bool RequestMetaDataTypeStateMachine::_uriIsMAVLinkFTP(const QString& uri)
604{
605 return uri.startsWith(QStringLiteral("%1://").arg(FTPManager::mavlinkFTPScheme), Qt::CaseInsensitive);
606}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Cached file download with time-based expiration and fallback support.
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void complete()
Call this to signal that the async operation has completed successfully.
Base class for all CompInfo types.
Definition CompInfo.h:14
const COMP_METADATA_TYPE type
Definition CompInfo.h:35
const QString & uriMetaData() const
Definition CompInfo.h:20
Vehicle *const vehicle
Definition CompInfo.h:36
virtual void setJson(const QString &metaDataJsonFileName)=0
const QString & uriTranslation() const
Definition CompInfo.h:22
uint32_t crcMetaData() const
Definition CompInfo.h:24
void setUriMetaData(const QString &uri, uint32_t crc)
Definition CompInfo.cc:12
uint32_t crcMetaDataFallback() const
Definition CompInfo.h:25
bool crcMetaDataValid() const
Definition CompInfo.h:26
const QString & uriMetaDataFallback() const
Definition CompInfo.h:21
bool available() const
Definition CompInfo.h:33
bool crcMetaDataFallbackValid() const
Definition CompInfo.h:27
QString insert(const QString &fileTag, const QString &fileName)
QString access(const QString &fileTag)
ComponentInformationTranslation * translation()
static constexpr int cachedFileMaxAgeSec
3 days
ComponentInformationCache & fileCache()
void downloadComplete(QString translatedJsonTempFile, QString errorMsg)
bool downloadAndTranslate(const QString &summaryJsonFile, const QString &toTranslateJsonFile, int maxCacheAgeSec, const QString &componentName)
@ EmitError
Emit error() signal (default)
void cancelDownload()
static constexpr const char * mavlinkFTPScheme
Definition FTPManager.h:78
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
bool download(const QString &url, int maxCacheAgeSec)
void finished(bool success, const QString &localPath, const QString &errorMessage, bool fromCache)
QGroundControl specific state machine with enhanced error handling.
void start()
Start the state machine with debug logging.
void skipped()
Emitted when skip predicate returns true and the state is skipped.
void complete()
Call this to signal that the async operation has completed successfully.
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageFailureMessageNotReceived
Definition Vehicle.h:672
@ RequestMessageFailureCommandNotAcked
Definition Vehicle.h:671
@ RequestMessageFailureCommandError
Definition Vehicle.h:670
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
Definition Vehicle.cc:3099
FTPManager * ftpManager()
Definition Vehicle.h:581
void completed()
QString decompressIfNeeded(const QString &filePath, const QString &outputPath, bool removeOriginal)