31 _wireProgressTracking();
32 _wireTimeoutHandling();
34 setInitialState(_stateAutopilotVersion);
47void InitialConnectStateMachine::_createStates()
51 QStringLiteral(
"RequestAutopilotVersion"),
53 MAVLINK_MSG_ID_AUTOPILOT_VERSION,
55 _handleAutopilotVersionSuccess(message);
58 MAV_COMP_ID_AUTOPILOT1,
59 _timeoutAutopilotVersion
62 return _shouldSkipAutopilotVersionRequest();
65 _handleAutopilotVersionFailure();
70 QStringLiteral(
"RequestStandardModes"),
78 QStringLiteral(
"RequestCompInfo"),
86 QStringLiteral(
"RequestParameters"),
89 if (_shouldSkipForFlying()) {
94 _lastSkipReason = QStringLiteral(
"(vehicle is flying)");
101 qCDebug(InitialConnectStateMachineLog) <<
"Skipping parameter download" << _lastSkipReason;
109 QStringLiteral(
"RequestMission"),
111 [
this]() {
return _shouldSkipForPlanLoad(); },
114 qCDebug(InitialConnectStateMachineLog) <<
"Skipping mission load" << _lastSkipReason;
121 QStringLiteral(
"RequestGeoFence"),
124 if (_shouldSkipForPlanLoad()) {
127 if (!
vehicle()->_geoFenceManager->supported()) {
128 _lastSkipReason = QStringLiteral(
"(not supported by vehicle)");
135 qCDebug(InitialConnectStateMachineLog) <<
"Skipping geofence load" << _lastSkipReason;
142 QStringLiteral(
"RequestRallyPoints"),
145 if (_shouldSkipForPlanLoad()) {
148 if (!
vehicle()->_rallyPointManager->supported()) {
149 _lastSkipReason = QStringLiteral(
"(not supported by vehicle)");
156 qCDebug(InitialConnectStateMachineLog) <<
"Skipping rally points load" << _lastSkipReason;
158 vehicle()->_initialPlanRequestComplete =
true;
168 QStringLiteral(
"SignalComplete"),
180 _stateFinal =
new QGCFinalState(QStringLiteral(
"Final"),
this);
183void InitialConnectStateMachine::_wireTransitions()
208void InitialConnectStateMachine::_wireProgressTracking()
213 {_stateAutopilotVersion, 1},
214 {_stateStandardModes, 1},
216 {_stateParameters, 5},
219 {_stateRallyPoints, 1},
224void InitialConnectStateMachine::_onSubProgressUpdate(
double progressValue)
233void InitialConnectStateMachine::_wireTimeoutHandling()
239 [
this]() { _requestStandardModes(_stateStandardModes); }, _maxRetries);
242 [
this]() { _requestCompInfo(_stateCompInfo); }, _maxRetries);
245 [
this]() { _requestParameters(_stateParameters); }, _maxRetries);
248 [
this]() { _requestMission(_stateMission); }, _maxRetries);
251 [
this]() { _requestGeoFence(_stateGeoFence); }, _maxRetries);
254 [
this]() { _requestRallyPoints(_stateRallyPoints); }, _maxRetries);
261bool InitialConnectStateMachine::_shouldSkipAutopilotVersionRequest()
const
265 qCDebug(InitialConnectStateMachineLog) <<
"Skipping AUTOPILOT_VERSION: no primary link";
268 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
269 qCDebug(InitialConnectStateMachineLog) <<
"Skipping AUTOPILOT_VERSION: high latency or log replay";
275bool InitialConnectStateMachine::_shouldSkipForFlying()
const
286bool InitialConnectStateMachine::_shouldSkipForLinkType()
const
292 return sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay();
295bool InitialConnectStateMachine::_hasPrimaryLink()
const
298 return sharedLink !=
nullptr;
301bool InitialConnectStateMachine::_shouldSkipForPlanLoad()
303 if (_shouldSkipForFlying()) {
304 _lastSkipReason = QStringLiteral(
"(vehicle is flying)");
307 if (!_hasPrimaryLink()) {
308 _lastSkipReason = QStringLiteral(
"(no primary link)");
311 if (_shouldSkipForLinkType()) {
312 _lastSkipReason = QStringLiteral(
"(high latency or log replay link)");
322void InitialConnectStateMachine::_handleAutopilotVersionSuccess(
const mavlink_message_t& message)
324 qCDebug(InitialConnectStateMachineLog) <<
"AUTOPILOT_VERSION received";
326 mavlink_autopilot_version_t autopilotVersion;
327 mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);
329 vehicle()->_uid = (quint64)autopilotVersion.uid;
330 vehicle()->_firmwareBoardVendorId = autopilotVersion.vendor_id;
331 vehicle()->_firmwareBoardProductId = autopilotVersion.product_id;
334 if (autopilotVersion.flight_sw_version != 0) {
335 int majorVersion, minorVersion, patchVersion;
336 FIRMWARE_VERSION_TYPE versionType;
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);
345 if (
vehicle()->px4Firmware()) {
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];
355 for (
int i = 7; i >= 0; i--) {
356 vehicle()->_gitHash.append(QString(
"%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar(
'0')));
361 strncpy(nullStr, (
char*)autopilotVersion.flight_custom_version, 8);
367 vehicle()->_checkLatestStableFWDone =
true;
372 vehicle()->_setCapabilities(autopilotVersion.capabilities);
375void InitialConnectStateMachine::_handleAutopilotVersionFailure()
377 qCDebug(InitialConnectStateMachineLog) <<
"AUTOPILOT_VERSION request failed, setting assumed capabilities";
379 uint64_t assumedCapabilities = MAV_PROTOCOL_CAPABILITY_MAVLINK2;
382 assumedCapabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT | MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
383 MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
385 vehicle()->_setCapabilities(assumedCapabilities);
390 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestStandardModes";
398 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestCompInfo";
401 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
406 this, &InitialConnectStateMachine::_onSubProgressUpdate);
410 [](
void* requestAllCompleteFnData) {
412 if (self->_stateCompInfo) {
422 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestParameters";
424 const bool cacheOnly = _shouldSkipForFlying();
425 QMetaObject::Connection cacheFailedConn;
429 state, [state,
this]() {
430 qCDebug(InitialConnectStateMachineLog) <<
"Parameter cache check failed while flying, advancing without parameters";
437 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
440 [
this](
bool parametersReady) {
441 _onParametersReady(parametersReady);
445 state->
setOnExit([
this, cacheFailedConn]() {
447 this, &InitialConnectStateMachine::_onSubProgressUpdate);
448 if (cacheFailedConn) {
449 disconnect(cacheFailedConn);
460void InitialConnectStateMachine::_onParametersReady(
bool parametersReady)
462 qCDebug(InitialConnectStateMachineLog) <<
"_onParametersReady" << parametersReady;
466 this, &InitialConnectStateMachine::_onSubProgressUpdate);
468 if (parametersReady) {
470 vehicle()->_sendQGCTimeToVehicle();
471 vehicle()->_sendQGCTimeToVehicle();
474 vehicle()->_setupAutoDisarmSignalling();
478 if (_stateParameters) {
486 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestMission";
489 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
496 this, &InitialConnectStateMachine::_onSubProgressUpdate);
504 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestGeoFence";
507 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
514 this, &InitialConnectStateMachine::_onSubProgressUpdate);
522 qCDebug(InitialConnectStateMachineLog) <<
"_stateRequestRallyPoints";
525 this, &InitialConnectStateMachine::_onSubProgressUpdate, Qt::UniqueConnection);
530 vehicle()->_initialPlanRequestComplete =
true;
533 if (_stateRallyPoints) {
541 this, &InitialConnectStateMachine::_onSubProgressUpdate);
547void InitialConnectStateMachine::_signalComplete()
549 qCDebug(InitialConnectStateMachineLog) <<
"Signalling initialConnectComplete";
550 connect(
this, &QStateMachine::finished,
vehicle(), [
this]() {
552 }, Qt::SingleShotConnection);
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.
virtual void checkIfIsLatestStable(Vehicle *vehicle) const
Used to check if running firmware is latest stable version.
State machine for initial vehicle connection sequence.
~InitialConnectStateMachine() override
void setParameterDownloadSkipped(bool skipped)
void parametersReadyChanged(bool parametersReady)
void tryHashCheckCacheLoad()
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)
A state that retries an action and chooses behavior when retries are exhausted.
@ EmitError
Emit error() after retries exhausted.
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.
WeakLinkInterfacePtr primaryLink() const
MissionManager * _missionManager
void initialConnectComplete()
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
VehicleLinkManager * vehicleLinkManager()
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
GeoFenceManager * _geoFenceManager
void gitHashChanged(QString hash)
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
RallyPointManager * _rallyPointManager
StandardModes * _standardModes