QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ComponentInformationManager.cc
Go to the documentation of this file.
4#include "Vehicle.h"
5#include "CompInfoGeneral.h"
6#include "CompInfoParam.h"
7#include "CompInfoEvents.h"
8#include "CompInfoActuators.h"
10#include "QGCLoggingCategory.h"
11
12#include <QtCore/QStandardPaths>
13
14QGC_LOGGING_CATEGORY(ComponentInformationManagerLog, "ComponentInformation.ComponentInformationManager")
15
18 , _requestTypeStateMachine(this, this)
19 , _cachedFileDownload(new QGCCachedFileDownload(QStandardPaths::writableLocation(QStandardPaths::CacheLocation) + QLatin1String("/QGCCompInfoFileDownloadCache"), this))
20 , _fileCache(ComponentInformationCache::defaultInstance())
21 , _translation(new ComponentInformationTranslation(this, _cachedFileDownload))
22{
23 qCDebug(ComponentInformationManagerLog) << this;
24 qCDebug(ComponentInformationManagerLog) << "Cache location:" << QStandardPaths::writableLocation(QStandardPaths::CacheLocation) + QLatin1String("/QGCCompInfoCache");
25
26 _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_GENERAL] = new CompInfoGeneral (MAV_COMP_ID_AUTOPILOT1, vehicle, this);
27 _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_PARAMETER] = new CompInfoParam (MAV_COMP_ID_AUTOPILOT1, vehicle, this);
28 _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_EVENTS] = new CompInfoEvents (MAV_COMP_ID_AUTOPILOT1, vehicle, this);
29 _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_ACTUATORS] = new CompInfoActuators (MAV_COMP_ID_AUTOPILOT1, vehicle, this);
30
31 _createStates();
32 _wireTransitions();
33 _wireProgressTracking();
34
35 setInitialState(_stateRequestGeneral);
36}
37
39{
40 qCDebug(ComponentInformationManagerLog) << this;
41}
42
43void ComponentInformationManager::_createStates()
44{
45 // State 1: Request general component information
46 _stateRequestGeneral = new AsyncFunctionState(
47 QStringLiteral("RequestGeneral"),
48 this,
49 [this](AsyncFunctionState* state) { _requestCompInfoGeneral(state); }
50 );
51 registerState(_stateRequestGeneral);
52
53 // State 2: Update URIs after general info received
54 _stateUpdateUri = addFunctionState(
55 QStringLiteral("UpdateUri"),
56 [this]() { _updateAllUri(); }
57 );
58
59 // State 3: Request parameter metadata (skippable)
60 _stateRequestParam = new SkippableAsyncState(
61 QStringLiteral("RequestParam"),
62 this,
63 [this]() { return !_isCompTypeSupported(COMP_METADATA_TYPE_PARAMETER); },
64 [this](SkippableAsyncState* state) { _requestCompInfoParam(state); },
65 []() {
66 qCDebug(ComponentInformationManagerLog) << "Skipping parameter metadata, not supported";
67 }
68 );
69 registerState(_stateRequestParam);
70
71 // State 4: Request events metadata (skippable)
72 _stateRequestEvents = new SkippableAsyncState(
73 QStringLiteral("RequestEvents"),
74 this,
75 [this]() { return !_isCompTypeSupported(COMP_METADATA_TYPE_EVENTS); },
76 [this](SkippableAsyncState* state) { _requestCompInfoEvents(state); },
77 []() {
78 qCDebug(ComponentInformationManagerLog) << "Skipping events metadata, not supported";
79 }
80 );
81 registerState(_stateRequestEvents);
82
83 // State 5: Request actuators metadata (skippable)
84 _stateRequestActuators = new SkippableAsyncState(
85 QStringLiteral("RequestActuators"),
86 this,
87 [this]() { return !_isCompTypeSupported(COMP_METADATA_TYPE_ACTUATORS); },
88 [this](SkippableAsyncState* state) { _requestCompInfoActuators(state); },
89 []() {
90 qCDebug(ComponentInformationManagerLog) << "Skipping actuators metadata, not supported";
91 }
92 );
93 registerState(_stateRequestActuators);
94
95 // State 6: Signal completion
96 _stateComplete = addFunctionState(
97 QStringLiteral("Complete"),
98 [this]() { _signalComplete(); }
99 );
100
101 // Final state
102 _stateFinal = addFinalState(QStringLiteral("Final"));
103}
104
105void ComponentInformationManager::_wireTransitions()
106{
107 // RequestGeneral -> UpdateUri
108 _stateRequestGeneral->addTransition(_stateRequestGeneral, &AsyncFunctionState::advance, _stateUpdateUri);
109
110 // UpdateUri -> RequestParam
111 _stateUpdateUri->addTransition(_stateUpdateUri, &FunctionState::advance, _stateRequestParam);
112
113 // RequestParam -> RequestEvents (via advance or skipped)
114 _stateRequestParam->addTransition(_stateRequestParam, &SkippableAsyncState::advance, _stateRequestEvents);
115 _stateRequestParam->addTransition(_stateRequestParam, &SkippableAsyncState::skipped, _stateRequestEvents);
116
117 // RequestEvents -> RequestActuators (via advance or skipped)
118 _stateRequestEvents->addTransition(_stateRequestEvents, &SkippableAsyncState::advance, _stateRequestActuators);
119 _stateRequestEvents->addTransition(_stateRequestEvents, &SkippableAsyncState::skipped, _stateRequestActuators);
120
121 // RequestActuators -> Complete (via advance or skipped)
122 _stateRequestActuators->addTransition(_stateRequestActuators, &SkippableAsyncState::advance, _stateComplete);
123 _stateRequestActuators->addTransition(_stateRequestActuators, &SkippableAsyncState::skipped, _stateComplete);
124
125 // Complete -> Final
126 _stateComplete->addTransition(_stateComplete, &FunctionState::advance, _stateFinal);
127}
128
129void ComponentInformationManager::_wireProgressTracking()
130{
131 _stateRequestGeneral->setOnEntry([this]() {
132 _currentStateIndex = 0;
133 _updateProgress();
134 });
135
136 _stateUpdateUri->setOnEntry([this]() {
137 _currentStateIndex = 1;
138 _updateProgress();
139 });
140
141 _stateRequestParam->setOnEntry([this]() {
142 _currentStateIndex = 2;
143 _updateProgress();
144 });
145
146 _stateRequestEvents->setOnEntry([this]() {
147 _currentStateIndex = 3;
148 _updateProgress();
149 });
150
151 _stateRequestActuators->setOnEntry([this]() {
152 _currentStateIndex = 4;
153 _updateProgress();
154 });
155
156 _stateComplete->setOnEntry([this]() {
157 _currentStateIndex = 5;
158 _updateProgress();
159 });
160}
161
162void ComponentInformationManager::_updateProgress()
163{
164 emit progressUpdate(progress());
165}
166
168{
169 if (!isRunning()) {
170 return 1.0f;
171 }
172 return static_cast<float>(_currentStateIndex) / static_cast<float>(_stateCount);
173}
174
175void ComponentInformationManager::requestAllComponentInformation(RequestAllCompleteFn requestAllCompletFn, void * requestAllCompleteFnData)
176{
177 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
178
179 _requestAllCompleteFn = requestAllCompletFn;
180 _requestAllCompleteFnData = requestAllCompleteFnData;
181
182 // Guard against double-start: when InitialConnectStateMachine's CompInfo
183 // state times out, the retry callback re-invokes this method while the CIM
184 // state machine is still running. Only start if not already in progress;
185 // the updated callback pointers above are sufficient for the retry path.
186 if (!isRunning()) {
187 start();
188 }
189 emit progressUpdate(progress());
190}
191
192void ComponentInformationManager::_requestCompInfoGeneral(AsyncFunctionState* state)
193{
194 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
195
196 // Connect to requestComplete signal to advance when done
198
199 _requestTypeStateMachine.request(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_GENERAL]);
200}
201
202void ComponentInformationManager::_updateAllUri()
203{
204 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
205
206 CompInfoGeneral* general = qobject_cast<CompInfoGeneral*>(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_GENERAL]);
207 for (auto& compInfo : _compInfoMap[MAV_COMP_ID_AUTOPILOT1]) {
208 general->setUris(*compInfo);
209 }
210}
211
212void ComponentInformationManager::_requestCompInfoParam(SkippableAsyncState* state)
213{
214 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
215
217 _requestTypeStateMachine.request(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_PARAMETER]);
218}
219
220void ComponentInformationManager::_requestCompInfoEvents(SkippableAsyncState* state)
221{
222 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
223
225 _requestTypeStateMachine.request(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_EVENTS]);
226}
227
228void ComponentInformationManager::_requestCompInfoActuators(SkippableAsyncState* state)
229{
230 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
231
233 _requestTypeStateMachine.request(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_ACTUATORS]);
234}
235
236void ComponentInformationManager::_signalComplete()
237{
238 qCDebug(ComponentInformationManagerLog) << Q_FUNC_INFO;
239
240 if (_requestAllCompleteFn) {
241 (*_requestAllCompleteFn)(_requestAllCompleteFnData);
242 _requestAllCompleteFn = nullptr;
243 _requestAllCompleteFnData = nullptr;
244 }
245}
246
247bool ComponentInformationManager::_isCompTypeSupported(COMP_METADATA_TYPE type) const
248{
249 CompInfoGeneral* general = qobject_cast<CompInfoGeneral*>(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_GENERAL]);
250 return general ? general->isMetaDataTypeSupported(type) : false;
251}
252
254{
255 if (!_compInfoMap.contains(compId)) {
256 // Create default info
257 _compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER] = new CompInfoParam(compId, vehicle(), this);
258 }
259 return qobject_cast<CompInfoParam*>(_compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER]);
260}
261
263{
264 return _compInfoMap.contains(compId) && _compInfoMap[compId].contains(COMP_METADATA_TYPE_GENERAL) ? qobject_cast<CompInfoGeneral*>(_compInfoMap[compId][COMP_METADATA_TYPE_GENERAL]) : nullptr;
265}
266
267QString ComponentInformationManager::_getFileCacheTag(int compInfoType, uint32_t crc, bool isTranslation)
268{
269 return QString::asprintf("%08x_%02i_%i", crc, compInfoType, (int)isTranslation);
270}
Cached file download with time-based expiration and fallback support.
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void connectToCompletion(typename QtPrivate::FunctionPointer< Func >::Object *sender, Func signal)
bool isMetaDataTypeSupported(COMP_METADATA_TYPE metadataType)
void setUris(CompInfo &compInfo) const
CompInfoParam * compInfoParam(uint8_t compId)
void progressUpdate(float progress)
CompInfoGeneral * compInfoGeneral(uint8_t compId)
void requestAllComponentInformation(RequestAllCompleteFn requestAllCompletFn, void *requestAllCompleteFnData)
void setOnEntry(EntryCallback callback)
Set a callback to be invoked when the state is entered.
QGroundControl specific state machine with enhanced error handling.
void start()
Start the state machine with debug logging.
void connectToCompletion(typename QtPrivate::FunctionPointer< Func >::Object *sender, Func signal)
void skipped()
Emitted when skip predicate returns true and the state is skipped.