QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
InitialConnectStateMachine.cc
Go to the documentation of this file.
2#include "MAVLinkLib.h"
3#include "Vehicle.h"
5#include "QGCCorePlugin.h"
6#include "QGCOptions.h"
7#include "FirmwarePlugin.h"
8#include "ParameterManager.h"
10#include "MissionManager.h"
11#include "StandardModes.h"
12#include "GeoFenceManager.h"
13#include "RallyPointManager.h"
14#include "QGCLoggingCategory.h"
15#include "SettingsManager.h"
16#include "MavlinkSettings.h"
17
18#include <cstring>
19
20QGC_LOGGING_CATEGORY(InitialConnectStateMachineLog, "Vehicle.InitialConnectStateMachine")
21
22// ============================================================================
23// InitialConnectStateMachine Implementation
24// ============================================================================
25
27 : QGCStateMachine(QStringLiteral("InitialConnectStateMachine"), vehicle, parent)
28{
29 _createStates();
30 _wireTransitions();
31 _wireProgressTracking();
32 _wireTimeoutHandling();
33
34 setInitialState(_stateAutopilotVersion);
35}
36
40
46
47void InitialConnectStateMachine::_createStates()
48{
49 // State 0: Request autopilot version
50 _stateAutopilotVersion = new RetryableRequestMessageState(
51 QStringLiteral("RequestAutopilotVersion"),
52 this,
53 MAVLINK_MSG_ID_AUTOPILOT_VERSION,
54 [this](Vehicle*, const mavlink_message_t& message) {
55 _handleAutopilotVersionSuccess(message);
56 },
57 _maxRetries,
58 MAV_COMP_ID_AUTOPILOT1,
59 _timeoutAutopilotVersion
60 );
61 _stateAutopilotVersion->setSkipPredicate([this]() {
62 return _shouldSkipAutopilotVersionRequest();
63 });
64 _stateAutopilotVersion->setFailureHandler([this](auto, auto) {
65 _handleAutopilotVersionFailure();
66 });
67
68 // State 1: Request standard modes
69 _stateStandardModes = new AsyncFunctionState(
70 QStringLiteral("RequestStandardModes"),
71 this,
72 [this](AsyncFunctionState* state) { _requestStandardModes(state); },
73 _timeoutStandardModes
74 );
75
76 // State 2: Request component information
77 _stateCompInfo = new AsyncFunctionState(
78 QStringLiteral("RequestCompInfo"),
79 this,
80 [this](AsyncFunctionState* state) { _requestCompInfo(state); },
81 _timeoutCompInfo
82 );
83
84 // State 3: Request parameters (skippable)
85 _stateParameters = new SkippableAsyncState(
86 QStringLiteral("RequestParameters"),
87 this,
88 [this]() {
89 if (_shouldSkipForFlying()) {
90 // PX4 can try a lightweight hash-check cache load
91 if (vehicle()->px4Firmware()) {
92 return false;
93 }
94 _lastSkipReason = QStringLiteral("(vehicle is flying)");
95 return true;
96 }
97 return false;
98 },
99 [this](SkippableAsyncState* state) { _requestParameters(state); },
100 [this]() {
101 qCDebug(InitialConnectStateMachineLog) << "Skipping parameter download" << _lastSkipReason;
102 vehicle()->_parameterManager->setParameterDownloadSkipped(true);
103 },
104 _timeoutParameters
105 );
106
107 // State 4: Request mission (skippable)
108 _stateMission = new SkippableAsyncState(
109 QStringLiteral("RequestMission"),
110 this,
111 [this]() { return _shouldSkipForPlanLoad(); },
112 [this](SkippableAsyncState* state) { _requestMission(state); },
113 [this]() {
114 qCDebug(InitialConnectStateMachineLog) << "Skipping mission load" << _lastSkipReason;
115 },
116 _timeoutMission
117 );
118
119 // State 5: Request geofence (skippable)
120 _stateGeoFence = new SkippableAsyncState(
121 QStringLiteral("RequestGeoFence"),
122 this,
123 [this]() {
124 if (_shouldSkipForPlanLoad()) {
125 return true;
126 }
127 if (!vehicle()->_geoFenceManager->supported()) {
128 _lastSkipReason = QStringLiteral("(not supported by vehicle)");
129 return true;
130 }
131 return false;
132 },
133 [this](SkippableAsyncState* state) { _requestGeoFence(state); },
134 [this]() {
135 qCDebug(InitialConnectStateMachineLog) << "Skipping geofence load" << _lastSkipReason;
136 },
137 _timeoutGeoFence
138 );
139
140 // State 6: Request rally points (skippable)
141 _stateRallyPoints = new SkippableAsyncState(
142 QStringLiteral("RequestRallyPoints"),
143 this,
144 [this]() {
145 if (_shouldSkipForPlanLoad()) {
146 return true;
147 }
148 if (!vehicle()->_rallyPointManager->supported()) {
149 _lastSkipReason = QStringLiteral("(not supported by vehicle)");
150 return true;
151 }
152 return false;
153 },
154 [this](SkippableAsyncState* state) { _requestRallyPoints(state); },
155 [this]() {
156 qCDebug(InitialConnectStateMachineLog) << "Skipping rally points load" << _lastSkipReason;
157 // Mark plan request complete when skipping
158 vehicle()->_initialPlanRequestComplete = true;
160 },
161 _timeoutRallyPoints
162 );
163
164 // State 7: Signal completion
165 // Use RetryState with zero retries so completion participates in the unified
166 // retry/error state family while preserving immediate success behavior.
167 _stateComplete = new RetryState(
168 QStringLiteral("SignalComplete"),
169 this,
170 [this]() {
171 _signalComplete();
172 return true;
173 },
174 0,
175 0,
177 );
178
179 // Final state
180 _stateFinal = new QGCFinalState(QStringLiteral("Final"), this);
181}
182
183void InitialConnectStateMachine::_wireTransitions()
184{
185 // Linear progression - use completed() for WaitStateBase-derived states (more semantic)
186 _stateAutopilotVersion->addTransition(_stateAutopilotVersion, &WaitStateBase::completed, _stateStandardModes);
187 _stateStandardModes->addTransition(_stateStandardModes, &WaitStateBase::completed, _stateCompInfo);
188 _stateCompInfo->addTransition(_stateCompInfo, &WaitStateBase::completed, _stateParameters);
189
190 // SkippableAsyncStates: both completed and skipped go to next state
191
192 _stateParameters->addTransition(_stateParameters, &WaitStateBase::completed, _stateMission);
193 _stateParameters->addTransition(_stateParameters, &SkippableAsyncState::skipped, _stateMission);
194
195 _stateMission->addTransition(_stateMission, &WaitStateBase::completed, _stateGeoFence);
196 _stateMission->addTransition(_stateMission, &SkippableAsyncState::skipped, _stateGeoFence);
197
198 _stateGeoFence->addTransition(_stateGeoFence, &WaitStateBase::completed, _stateRallyPoints);
199 _stateGeoFence->addTransition(_stateGeoFence, &SkippableAsyncState::skipped, _stateRallyPoints);
200
201 _stateRallyPoints->addTransition(_stateRallyPoints, &WaitStateBase::completed, _stateComplete);
202 _stateRallyPoints->addTransition(_stateRallyPoints, &SkippableAsyncState::skipped, _stateComplete);
203
204 // Complete -> Final (RetryState emits advance() on success)
205 _stateComplete->addTransition(_stateComplete, &QGCState::advance, _stateFinal);
206}
207
208void InitialConnectStateMachine::_wireProgressTracking()
209{
210 // Use QGCStateMachine's built-in weighted progress tracking
211 // Progress is automatically updated when states are entered
213 {_stateAutopilotVersion, 1},
214 {_stateStandardModes, 1},
215 {_stateCompInfo, 5},
216 {_stateParameters, 5},
217 {_stateMission, 2},
218 {_stateGeoFence, 1},
219 {_stateRallyPoints, 1},
220 {_stateComplete, 1}
221 });
222}
223
224void InitialConnectStateMachine::_onSubProgressUpdate(double progressValue)
225{
226 setSubProgress(static_cast<float>(progressValue));
227}
228
229// ============================================================================
230// Timeout Handling
231// ============================================================================
232
233void InitialConnectStateMachine::_wireTimeoutHandling()
234{
235 // Note: _stateAutopilotVersion is RetryableRequestMessageState which handles its own retry
236
237 // Use addRetryTransition builder for cleaner timeout handling
238 addRetryTransition(_stateStandardModes, &WaitStateBase::timedOut, _stateCompInfo,
239 [this]() { _requestStandardModes(_stateStandardModes); }, _maxRetries);
240
241 addRetryTransition(_stateCompInfo, &WaitStateBase::timedOut, _stateParameters,
242 [this]() { _requestCompInfo(_stateCompInfo); }, _maxRetries);
243
244 addRetryTransition(_stateParameters, &WaitStateBase::timedOut, _stateMission,
245 [this]() { _requestParameters(_stateParameters); }, _maxRetries);
246
247 addRetryTransition(_stateMission, &WaitStateBase::timedOut, _stateGeoFence,
248 [this]() { _requestMission(_stateMission); }, _maxRetries);
249
250 addRetryTransition(_stateGeoFence, &WaitStateBase::timedOut, _stateRallyPoints,
251 [this]() { _requestGeoFence(_stateGeoFence); }, _maxRetries);
252
253 addRetryTransition(_stateRallyPoints, &WaitStateBase::timedOut, _stateComplete,
254 [this]() { _requestRallyPoints(_stateRallyPoints); }, _maxRetries);
255}
256
257// ============================================================================
258// Skip Predicates
259// ============================================================================
260
261bool InitialConnectStateMachine::_shouldSkipAutopilotVersionRequest() const
262{
264 if (!sharedLink) {
265 qCDebug(InitialConnectStateMachineLog) << "Skipping AUTOPILOT_VERSION: no primary link";
266 return true;
267 }
268 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
269 qCDebug(InitialConnectStateMachineLog) << "Skipping AUTOPILOT_VERSION: high latency or log replay";
270 return true;
271 }
272 return false;
273}
274
275bool InitialConnectStateMachine::_shouldSkipForFlying() const
276{
277 if (!SettingsManager::instance()->mavlinkSettings()->noInitialDownloadWhenFlying()->rawValue().toBool()) {
278 return false;
279 }
280 // We use armed() rather than flying() as a surrogate for in-flight state because
281 // armed status is available immediately from the first heartbeat, whereas flying()
282 // depends on additional telemetry that may not have arrived yet at initial connect time.
283 return vehicle()->armed();
284}
285
286bool InitialConnectStateMachine::_shouldSkipForLinkType() const
287{
289 if (!sharedLink) {
290 return true;
291 }
292 return sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay();
293}
294
295bool InitialConnectStateMachine::_hasPrimaryLink() const
296{
298 return sharedLink != nullptr;
299}
300
301bool InitialConnectStateMachine::_shouldSkipForPlanLoad()
302{
303 if (_shouldSkipForFlying()) {
304 _lastSkipReason = QStringLiteral("(vehicle is flying)");
305 return true;
306 }
307 if (!_hasPrimaryLink()) {
308 _lastSkipReason = QStringLiteral("(no primary link)");
309 return true;
310 }
311 if (_shouldSkipForLinkType()) {
312 _lastSkipReason = QStringLiteral("(high latency or log replay link)");
313 return true;
314 }
315 return false;
316}
317
318// ============================================================================
319// State Callbacks
320// ============================================================================
321
322void InitialConnectStateMachine::_handleAutopilotVersionSuccess(const mavlink_message_t& message)
323{
324 qCDebug(InitialConnectStateMachineLog) << "AUTOPILOT_VERSION received";
325
326 mavlink_autopilot_version_t autopilotVersion;
327 mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
328
329 vehicle()->_uid = (quint64)autopilotVersion.uid;
330 vehicle()->_firmwareBoardVendorId = autopilotVersion.vendor_id;
331 vehicle()->_firmwareBoardProductId = autopilotVersion.product_id;
332 emit vehicle()->vehicleUIDChanged();
333
334 if (autopilotVersion.flight_sw_version != 0) {
335 int majorVersion, minorVersion, patchVersion;
336 FIRMWARE_VERSION_TYPE versionType;
337
338 majorVersion = (autopilotVersion.flight_sw_version >> (8*3)) & 0xFF;
339 minorVersion = (autopilotVersion.flight_sw_version >> (8*2)) & 0xFF;
340 patchVersion = (autopilotVersion.flight_sw_version >> (8*1)) & 0xFF;
341 versionType = (FIRMWARE_VERSION_TYPE)((autopilotVersion.flight_sw_version >> (8*0)) & 0xFF);
342 vehicle()->setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
343 }
344
345 if (vehicle()->px4Firmware()) {
346 // Lower 3 bytes is custom version
347 int majorVersion, minorVersion, patchVersion;
348 majorVersion = autopilotVersion.flight_custom_version[2];
349 minorVersion = autopilotVersion.flight_custom_version[1];
350 patchVersion = autopilotVersion.flight_custom_version[0];
351 vehicle()->setFirmwareCustomVersion(majorVersion, minorVersion, patchVersion);
352
353 // PX4 Firmware stores the first 16 characters of the git hash as binary, with the individual bytes in reverse order
354 vehicle()->_gitHash = "";
355 for (int i = 7; i >= 0; i--) {
356 vehicle()->_gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
357 }
358 } else {
359 // APM Firmware stores the first 8 characters of the git hash as an ASCII character string
360 char nullStr[9];
361 strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
362 nullStr[8] = 0;
363 vehicle()->_gitHash = nullStr;
364 }
365
366 if (QGCCorePlugin::instance()->options()->checkFirmwareVersion() && !vehicle()->_checkLatestStableFWDone) {
367 vehicle()->_checkLatestStableFWDone = true;
368 vehicle()->_firmwarePlugin->checkIfIsLatestStable(vehicle());
369 }
370 emit vehicle()->gitHashChanged(vehicle()->_gitHash);
371
372 vehicle()->_setCapabilities(autopilotVersion.capabilities);
373}
374
375void InitialConnectStateMachine::_handleAutopilotVersionFailure()
376{
377 qCDebug(InitialConnectStateMachineLog) << "AUTOPILOT_VERSION request failed, setting assumed capabilities";
378
379 uint64_t assumedCapabilities = MAV_PROTOCOL_CAPABILITY_MAVLINK2;
380 if (vehicle()->px4Firmware() || vehicle()->apmFirmware()) {
381 // We make some assumptions for known firmware
382 assumedCapabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT | MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
383 MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
384 }
385 vehicle()->_setCapabilities(assumedCapabilities);
386}
387
388void InitialConnectStateMachine::_requestStandardModes(AsyncFunctionState* state)
389{
390 qCDebug(InitialConnectStateMachineLog) << "_stateRequestStandardModes";
391
394}
395
396void InitialConnectStateMachine::_requestCompInfo(AsyncFunctionState* state)
397{
398 qCDebug(InitialConnectStateMachineLog) << "_stateRequestCompInfo";
399
400 connect(vehicle()->_componentInformationManager, &ComponentInformationManager::progressUpdate,
401 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
402
403 // Ensure progress tracking is always cleaned up, including timeout/skip paths.
404 state->setOnExit([this]() {
405 disconnect(vehicle()->_componentInformationManager, &ComponentInformationManager::progressUpdate,
406 this, &InitialConnectStateMachine::_onSubProgressUpdate);
407 });
408
409 vehicle()->_componentInformationManager->requestAllComponentInformation(
410 [](void* requestAllCompleteFnData) {
411 auto* self = static_cast<InitialConnectStateMachine*>(requestAllCompleteFnData);
412 if (self->_stateCompInfo) {
413 self->_stateCompInfo->complete();
414 }
415 },
416 this
417 );
418}
419
420void InitialConnectStateMachine::_requestParameters(SkippableAsyncState* state)
421{
422 qCDebug(InitialConnectStateMachineLog) << "_stateRequestParameters";
423
424 const bool cacheOnly = _shouldSkipForFlying();
425 QMetaObject::Connection cacheFailedConn;
426 if (cacheOnly) {
427 // If cache-only check fails (miss/timeout/non-PX4), complete the state without params
428 cacheFailedConn = connect(vehicle()->_parameterManager, &ParameterManager::cacheCheckOnlyFailed,
429 state, [state, this]() {
430 qCDebug(InitialConnectStateMachineLog) << "Parameter cache check failed while flying, advancing without parameters";
431 vehicle()->_parameterManager->setParameterDownloadSkipped(true);
432 state->complete();
433 });
434 }
435
436 connect(vehicle()->_parameterManager, &ParameterManager::loadProgressChanged,
437 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
438
440 [this](bool parametersReady) {
441 _onParametersReady(parametersReady);
442 });
443
444 // Ensure progress tracking is always cleaned up, including timeout/skip paths.
445 state->setOnExit([this, cacheFailedConn]() {
446 disconnect(vehicle()->_parameterManager, &ParameterManager::loadProgressChanged,
447 this, &InitialConnectStateMachine::_onSubProgressUpdate);
448 if (cacheFailedConn) {
449 disconnect(cacheFailedConn);
450 }
451 });
452
453 if (cacheOnly) {
454 vehicle()->_parameterManager->tryHashCheckCacheLoad();
455 } else {
456 vehicle()->_parameterManager->refreshAllParameters(MAV_COMP_ID_ALL);
457 }
458}
459
460void InitialConnectStateMachine::_onParametersReady(bool parametersReady)
461{
462 qCDebug(InitialConnectStateMachineLog) << "_onParametersReady" << parametersReady;
463
464 // Disconnect progress tracking from parameter manager
465 disconnect(vehicle()->_parameterManager, &ParameterManager::loadProgressChanged,
466 this, &InitialConnectStateMachine::_onSubProgressUpdate);
467
468 if (parametersReady) {
469 // Send time to vehicle (twice for reliability on noisy links)
470 vehicle()->_sendQGCTimeToVehicle();
471 vehicle()->_sendQGCTimeToVehicle();
472
473 // Set up auto-disarm signalling
474 vehicle()->_setupAutoDisarmSignalling();
475
476 // Note: Speed limits are handled by Vehicle::_parametersReady
477
478 if (_stateParameters) {
479 _stateParameters->complete();
480 }
481 }
482}
483
484void InitialConnectStateMachine::_requestMission(SkippableAsyncState* state)
485{
486 qCDebug(InitialConnectStateMachineLog) << "_stateRequestMission";
487
488 connect(vehicle()->_missionManager, &MissionManager::progressPctChanged,
489 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
490
492
493 // Disconnect progress tracking on exit
494 state->setOnExit([this]() {
495 disconnect(vehicle()->_missionManager, &MissionManager::progressPctChanged,
496 this, &InitialConnectStateMachine::_onSubProgressUpdate);
497 });
498
500}
501
502void InitialConnectStateMachine::_requestGeoFence(SkippableAsyncState* state)
503{
504 qCDebug(InitialConnectStateMachineLog) << "_stateRequestGeoFence";
505
506 connect(vehicle()->_geoFenceManager, &GeoFenceManager::progressPctChanged,
507 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
508
509 state->connectToCompletion(vehicle()->_geoFenceManager, &GeoFenceManager::loadComplete);
510
511 // Disconnect progress tracking on exit
512 state->setOnExit([this]() {
513 disconnect(vehicle()->_geoFenceManager, &GeoFenceManager::progressPctChanged,
514 this, &InitialConnectStateMachine::_onSubProgressUpdate);
515 });
516
518}
519
520void InitialConnectStateMachine::_requestRallyPoints(SkippableAsyncState* state)
521{
522 qCDebug(InitialConnectStateMachineLog) << "_stateRequestRallyPoints";
523
524 connect(vehicle()->_rallyPointManager, &RallyPointManager::progressPctChanged,
525 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
526
527 state->connectToCompletion(vehicle()->_rallyPointManager, &RallyPointManager::loadComplete,
528 [this]() {
529 // Mark initial plan request complete
530 vehicle()->_initialPlanRequestComplete = true;
532
533 if (_stateRallyPoints) {
534 _stateRallyPoints->complete();
535 }
536 });
537
538 // Always clean up progress tracking when leaving this state.
539 state->setOnExit([this]() {
540 disconnect(vehicle()->_rallyPointManager, &RallyPointManager::progressPctChanged,
541 this, &InitialConnectStateMachine::_onSubProgressUpdate);
542 });
543
545}
546
547void InitialConnectStateMachine::_signalComplete()
548{
549 qCDebug(InitialConnectStateMachineLog) << "Signalling initialConnectComplete";
550 connect(this, &QStateMachine::finished, vehicle(), [this]() {
552 }, Qt::SingleShotConnection);
553}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Calls a function when entered and waits for an external trigger to advance.
void connectToCompletion(typename QtPrivate::FunctionPointer< Func >::Object *sender, Func signal)
void complete()
Call this to signal that the async operation has completed successfully.
void progressUpdate(float progress)
void requestAllComponentInformation(RequestAllCompleteFn requestAllCompletFn, void *requestAllCompleteFnData)
virtual void checkIfIsLatestStable(Vehicle *vehicle) const
Used to check if running firmware is latest stable version.
void loadComplete(void)
State machine for initial vehicle connection sequence.
void setParameterDownloadSkipped(bool skipped)
void parametersReadyChanged(bool parametersReady)
void refreshAllParameters(uint8_t componentID)
Re-request the full set of parameters from the autopilot.
void loadProgressChanged(float value)
void cacheCheckOnlyFailed()
void newMissionItemsAvailable(bool removeAllRequested)
void loadFromVehicle(void)
void progressPctChanged(double progressPercentPct)
void setOnExit(ExitCallback callback)
Set a callback to be invoked when the state is exited.
static QGCCorePlugin * instance()
Final state for a QGCStateMachine with logging support.
QGroundControl specific state machine with enhanced error handling.
void start()
Start the state machine with debug logging.
void setSubProgress(float subProgress)
Vehicle * vehicle() const
void setProgressWeights(const QList< QPair< QAbstractState *, int > > &stateWeights)
void resetProgress()
Reset progress tracking (call when restarting the machine)
RetryTransition * addRetryTransition(SenderType *from, Func signal, QAbstractState *to, std::function< void()> retryAction, int maxRetries=1)
void loadComplete(void)
A state that retries an action and chooses behavior when retries are exhausted.
Definition RetryState.h:15
@ EmitError
Emit error() after retries exhausted.
Definition RetryState.h:23
Requests a MAVLink message with built-in retry logic.
void setSkipPredicate(SkipPredicate predicate)
void setFailureHandler(FailureHandler handler)
Set handler called when all retries fail.
static SettingsManager * instance()
Combines skip condition checking with async operation setup in a single state.
void connectToCompletion(typename QtPrivate::FunctionPointer< Func >::Object *sender, Func signal)
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.
void requestCompleted()
WeakLinkInterfacePtr primaryLink() const
MissionManager * _missionManager
Definition Vehicle.h:1113
void initialConnectComplete()
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
Definition Vehicle.cc:2281
void vehicleUIDChanged()
GeoFenceManager * _geoFenceManager
Definition Vehicle.h:1114
void gitHashChanged(QString hash)
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
Definition Vehicle.cc:2272
RallyPointManager * _rallyPointManager
Definition Vehicle.h:1115
bool armed() const
Definition Vehicle.h:449
StandardModes * _standardModes
Definition Vehicle.h:1121
void completed()