QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RetryableRequestMessageState.cc
Go to the documentation of this file.
2#include "QGCStateMachine.h"
3
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QMetaObject>
6
7Q_DECLARE_LOGGING_CATEGORY(QGCStateMachineLog)
8
10 const QString& stateName,
11 QState* parent,
12 uint32_t messageId,
13 MessageHandler messageHandler,
14 int maxRetries,
15 int compId,
16 int timeoutMsecs)
17 : WaitStateBase(stateName, parent, timeoutMsecs)
18 , _messageId(messageId)
19 , _messageHandler(std::move(messageHandler))
20 , _compId(compId)
21 , _maxRetries(maxRetries)
22{
23}
24
26{
28 _retryCount = 0;
29
30 // Check skip predicate
31 if (_skipPredicate && _skipPredicate()) {
32 qCDebug(QGCStateMachineLog) << stateName() << "Skipping request (skip predicate returned true)";
34 return;
35 }
36
37 _sendRequest();
38}
39
41{
42 _requestActive = false;
44}
45
46void RetryableRequestMessageState::_sendRequest()
47{
48 Vehicle* v = vehicle();
49 if (!v) {
50 qCWarning(QGCStateMachineLog) << stateName() << "No vehicle available";
51 waitFailed();
52 return;
53 }
54
55 qCDebug(QGCStateMachineLog) << stateName() << "Requesting message" << _messageId
56 << "attempt" << (_retryCount + 1) << "of" << (_maxRetries + 1);
57
58 _requestActive = true;
60 [](void* resultHandlerData,
61 MAV_RESULT result,
63 const mavlink_message_t& message) {
64 auto* self = static_cast<RetryableRequestMessageState*>(resultHandlerData);
65 if (!self->_requestActive) {
66 return;
67 }
68 self->_handleResult(result, failureCode, message);
69 },
70 this,
71 _compId,
72 _messageId
73 );
74}
75
76void RetryableRequestMessageState::_queueRetry()
77{
78 // Defer retries so Vehicle can finish command-list cleanup from the prior callback.
79 // Immediate resend from within the callback can hit duplicate-request rejection.
80 QMetaObject::invokeMethod(this, [this]() {
81 if (!_requestActive) {
82 return;
83 }
84 _sendRequest();
85 }, Qt::QueuedConnection);
86}
87
88void RetryableRequestMessageState::_handleResult(
89 MAV_RESULT result,
91 const mavlink_message_t& message)
92{
93 Vehicle::RequestMessageResultHandlerFailureCode_t effectiveFailureCode = failureCode;
94 if (failureCode == Vehicle::RequestMessageFailureDuplicate) {
95 // Retryable request flows can re-enter while Vehicle still tracks the prior
96 // request as active. Treat duplicate as an in-flight timeout-equivalent.
98 }
99
100 _lastResult = result;
101 _lastFailureCode = effectiveFailureCode;
102
103 if (effectiveFailureCode == Vehicle::RequestMessageNoFailure) {
104 // Success
105 qCDebug(QGCStateMachineLog) << stateName() << "Message received successfully";
106
107 if (_messageHandler) {
108 _messageHandler(vehicle(), message);
109 }
110 emit messageReceived(message);
111 waitComplete();
112 return;
113 }
114
115 // Failure - check if we should retry
116 qCDebug(QGCStateMachineLog) << stateName() << "Request failed, failureCode:" << effectiveFailureCode;
117
118 if (_retryCount < _maxRetries) {
119 _retryCount++;
120 qCDebug(QGCStateMachineLog) << stateName() << "Retrying, attempt" << (_retryCount + 1);
121 _queueRetry();
122 } else {
123 // Max retries exhausted
124 qCWarning(QGCStateMachineLog) << stateName() << "Max retries exhausted";
125
126 if (_failureHandler) {
127 _failureHandler(effectiveFailureCode, result);
128 }
129 emit retriesExhausted();
130
131 if (_failOnMaxRetries) {
132 waitFailed();
133 } else {
134 waitComplete(); // Advance anyway (graceful degradation)
135 }
136 }
137}
138
140{
141 qCDebug(QGCStateMachineLog) << stateName() << "Timeout waiting for message";
142
144
145 if (_retryCount < _maxRetries) {
146 _retryCount++;
147 qCDebug(QGCStateMachineLog) << stateName() << "Retrying after timeout, attempt" << (_retryCount + 1);
148 _queueRetry();
149 } else {
150 qCWarning(QGCStateMachineLog) << stateName() << "Max retries exhausted after timeout";
151
152 if (_failureHandler) {
153 _failureHandler(_lastFailureCode, _lastResult);
154 }
155 emit retriesExhausted();
156
157 if (_failOnMaxRetries) {
158 WaitStateBase::onWaitTimeout(); // Emits timeout() and error()
159 } else {
160 waitComplete(); // Advance anyway
161 }
162 }
163}
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
void onWaitExited() override
Called when the state is exited - subclasses should call base implementation.
void messageReceived(const mavlink_message_t &message)
Emitted when message is successfully received.
void onWaitTimeout() override
Called when the timeout expires - default emits timeout(), subclasses can override.
void onWaitEntered() override
Called when the state is entered - subclasses should call base implementation.
void retriesExhausted()
Emitted when all retries are exhausted.
std::function< void(Vehicle *vehicle, const mavlink_message_t &message)> MessageHandler
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageFailureMessageNotReceived
Definition Vehicle.h:672
@ RequestMessageNoFailure
Definition Vehicle.h:669
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
Definition Vehicle.h:673
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
virtual void onWaitTimeout()
Called when the timeout expires - default emits timeout(), subclasses can override.
virtual void onWaitEntered()
Called when the state is entered - subclasses should call base implementation.
virtual void onWaitExited()
Called when the state is exited - subclasses should call base implementation.