6#include <QtCore/QMetaObject>
8QGC_LOGGING_CATEGORY(RetryableRequestMessageStateLog,
"Utilities.StateMachine.RetryableRequestMessageState")
11 const QString& stateName,
19 , _messageId(messageId)
20 , _messageHandler(std::move(messageHandler))
22 , _maxRetries(maxRetries)
32 if (_skipPredicate && _skipPredicate()) {
33 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Skipping request (skip predicate returned true)";
43 _requestActive =
false;
47void RetryableRequestMessageState::_sendRequest()
51 qCWarning(RetryableRequestMessageStateLog) <<
stateName() <<
"No vehicle available";
56 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Requesting message" << _messageId
57 <<
"attempt" << (_retryCount + 1) <<
"of" << (_maxRetries + 1);
59 _requestActive =
true;
61 [](
void* resultHandlerData,
66 if (!self->_requestActive) {
69 self->_handleResult(result, failureCode, message);
77void RetryableRequestMessageState::_queueRetry()
81 QMetaObject::invokeMethod(
this, [
this]() {
82 if (!_requestActive) {
86 }, Qt::QueuedConnection);
89void RetryableRequestMessageState::_handleResult(
101 _lastResult = result;
102 _lastFailureCode = effectiveFailureCode;
106 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Message received successfully";
108 if (_messageHandler) {
109 _messageHandler(
vehicle(), message);
117 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Request failed, failureCode:" << effectiveFailureCode;
119 if (_retryCount < _maxRetries) {
121 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Retrying, attempt" << (_retryCount + 1);
125 qCWarning(RetryableRequestMessageStateLog) <<
stateName() <<
"Max retries exhausted";
127 if (_failureHandler) {
128 _failureHandler(effectiveFailureCode, result);
132 if (_failOnMaxRetries) {
142 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Timeout waiting for message";
146 if (_retryCount < _maxRetries) {
148 qCDebug(RetryableRequestMessageStateLog) <<
stateName() <<
"Retrying after timeout, attempt" << (_retryCount + 1);
151 qCWarning(RetryableRequestMessageStateLog) <<
stateName() <<
"Max retries exhausted after timeout";
153 if (_failureHandler) {
154 _failureHandler(_lastFailureCode, _lastResult);
158 if (_failOnMaxRetries) {
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)
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