QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
InitialConnectStateMachine.h
Go to the documentation of this file.
1#pragma once
2
3#include "QGCStateMachine.h"
5
6class Vehicle;
10class RetryState;
11
22{
23 Q_OBJECT
24
25public:
26 explicit InitialConnectStateMachine(Vehicle* vehicle, QObject* parent = nullptr);
28
29 void start();
30
31private slots:
32 void _onSubProgressUpdate(double progressValue);
33
34private:
35 // State creation and wiring
36 void _createStates();
37 void _wireTransitions();
38 void _wireProgressTracking();
39 void _wireTimeoutHandling();
40
41 // State callbacks
42 void _handleAutopilotVersionSuccess(const mavlink_message_t& message);
43 void _handleAutopilotVersionFailure();
44 void _requestStandardModes(AsyncFunctionState* state);
45 void _requestCompInfo(AsyncFunctionState* state);
46 void _requestParameters(SkippableAsyncState* state);
47 void _onParametersReady(bool ready);
48 void _requestMission(SkippableAsyncState* state);
49 void _requestGeoFence(SkippableAsyncState* state);
50 void _requestRallyPoints(SkippableAsyncState* state);
51 void _signalComplete();
52
53 // Skip predicates
54 bool _shouldSkipAutopilotVersionRequest() const;
55 bool _shouldSkipForFlying() const;
56 bool _shouldSkipForLinkType() const;
57 bool _hasPrimaryLink() const;
58 bool _shouldSkipForPlanLoad();
59
60 QString _lastSkipReason;
61
62 // State pointers for wiring
63 RetryableRequestMessageState* _stateAutopilotVersion = nullptr;
64 AsyncFunctionState* _stateStandardModes = nullptr;
65 AsyncFunctionState* _stateCompInfo = nullptr;
66 SkippableAsyncState* _stateParameters = nullptr;
67 SkippableAsyncState* _stateMission = nullptr;
68 SkippableAsyncState* _stateGeoFence = nullptr;
69 SkippableAsyncState* _stateRallyPoints = nullptr;
70 RetryState* _stateComplete = nullptr;
71 QGCFinalState* _stateFinal = nullptr;
72
73 // Timeout handling with retry
74 static constexpr int _maxRetries = 1;
75
76 // Timeout values (ms)
77 static constexpr int _timeoutAutopilotVersion = 5000;
78 static constexpr int _timeoutStandardModes = 5000;
79 static constexpr int _timeoutCompInfo = 30000;
80 static constexpr int _timeoutParameters = 60000;
81 static constexpr int _timeoutMission = 30000;
82 static constexpr int _timeoutGeoFence = 15000;
83 static constexpr int _timeoutRallyPoints = 15000;
84};
struct __mavlink_message mavlink_message_t
Calls a function when entered and waits for an external trigger to advance.
State machine for initial vehicle connection sequence.
Final state for a QGCStateMachine with logging support.
QGroundControl specific state machine with enhanced error handling.
Vehicle * vehicle() const
A state that retries an action and chooses behavior when retries are exhausted.
Definition RetryState.h:15
Requests a MAVLink message with built-in retry logic.
Combines skip condition checking with async operation setup in a single state.