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#include "Vehicle.h"
4
6#include <QtCore/QMetaObject>
7
8QGC_LOGGING_CATEGORY(RetryableRequestMessageStateLog, "Utilities.StateMachine.RetryableRequestMessageState")
9
11 const QString& stateName,
12 QState* parent,
13 uint32_t messageId,
14 MessageHandler messageHandler,
15 int maxRetries,
16 int compId,
17 int timeoutMsecs)
18 : WaitStateBase(stateName, parent, timeoutMsecs)
19 , _messageId(messageId)
20 , _messageHandler(std::move(messageHandler))
21 , _compId(compId)
22 , _maxRetries(maxRetries)
23{
24}
25
27{
29 _retryCount = 0;
30
31 // Check skip predicate
32 if (_skipPredicate && _skipPredicate()) {
33 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Skipping request (skip predicate returned true)";
35 return;
36 }
37
38 _sendRequest();
39}
40
42{
43 _requestActive = false;
45}
46
47void RetryableRequestMessageState::_sendRequest()
48{
49 Vehicle* v = vehicle();
50 if (!v) {
51 qCWarning(RetryableRequestMessageStateLog) << stateName() << "No vehicle available";
52 waitFailed();
53 return;
54 }
55
56 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Requesting message" << _messageId
57 << "attempt" << (_retryCount + 1) << "of" << (_maxRetries + 1);
58
59 _requestActive = true;
61 [](void* resultHandlerData,
62 MAV_RESULT result,
64 const mavlink_message_t& message) {
65 auto* self = static_cast<RetryableRequestMessageState*>(resultHandlerData);
66 if (!self->_requestActive) {
67 return;
68 }
69 self->_handleResult(result, failureCode, message);
70 },
71 this,
72 _compId,
73 _messageId
74 );
75}
76
77void RetryableRequestMessageState::_queueRetry()
78{
79 // Defer retries so Vehicle can finish command-list cleanup from the prior callback.
80 // Immediate resend from within the callback can hit duplicate-request rejection.
81 QMetaObject::invokeMethod(this, [this]() {
82 if (!_requestActive) {
83 return;
84 }
85 _sendRequest();
86 }, Qt::QueuedConnection);
87}
88
89void RetryableRequestMessageState::_handleResult(
90 MAV_RESULT result,
92 const mavlink_message_t& message)
93{
94 VehicleTypes::RequestMessageResultHandlerFailureCode_t effectiveFailureCode = failureCode;
96 // Retryable request flows can re-enter while Vehicle still tracks the prior
97 // request as active. Treat duplicate as an in-flight timeout-equivalent.
99 }
100
101 _lastResult = result;
102 _lastFailureCode = effectiveFailureCode;
103
104 if (effectiveFailureCode == VehicleTypes::RequestMessageNoFailure) {
105 // Success
106 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Message received successfully";
107
108 if (_messageHandler) {
109 _messageHandler(vehicle(), message);
110 }
111 emit messageReceived(message);
112 waitComplete();
113 return;
114 }
115
116 // Failure - check if we should retry
117 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Request failed, failureCode:" << effectiveFailureCode;
118
119 if (_retryCount < _maxRetries) {
120 _retryCount++;
121 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Retrying, attempt" << (_retryCount + 1);
122 _queueRetry();
123 } else {
124 // Max retries exhausted
125 qCWarning(RetryableRequestMessageStateLog) << stateName() << "Max retries exhausted";
126
127 if (_failureHandler) {
128 _failureHandler(effectiveFailureCode, result);
129 }
130 emit retriesExhausted();
131
132 if (_failOnMaxRetries) {
133 waitFailed();
134 } else {
135 waitComplete(); // Advance anyway (graceful degradation)
136 }
137 }
138}
139
141{
142 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Timeout waiting for message";
143
145
146 if (_retryCount < _maxRetries) {
147 _retryCount++;
148 qCDebug(RetryableRequestMessageStateLog) << stateName() << "Retrying after timeout, attempt" << (_retryCount + 1);
149 _queueRetry();
150 } else {
151 qCWarning(RetryableRequestMessageStateLog) << stateName() << "Max retries exhausted after timeout";
152
153 if (_failureHandler) {
154 _failureHandler(_lastFailureCode, _lastResult);
155 }
156 emit retriesExhausted();
157
158 if (_failOnMaxRetries) {
159 WaitStateBase::onWaitTimeout(); // Emits timeout() and error()
160 } else {
161 waitComplete(); // Advance anyway
162 }
163 }
164}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
QString stateName() const
Vehicle * vehicle() const
Requests a MAVLink message with built-in retry logic.
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
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:2252
Base class for states that wait for something with optional timeout.
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.
RequestMessageResultHandlerFailureCode_t
@ RequestMessageFailureMessageNotReceived
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
@ RequestMessageNoFailure