4#include <QtCore/QLoggingCategory>
5#include <QtCore/QMetaObject>
10 const QString& stateName,
18 , _messageId(messageId)
19 , _messageHandler(std::move(messageHandler))
21 , _maxRetries(maxRetries)
31 if (_skipPredicate && _skipPredicate()) {
32 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Skipping request (skip predicate returned true)";
42 _requestActive =
false;
46void RetryableRequestMessageState::_sendRequest()
50 qCWarning(QGCStateMachineLog) <<
stateName() <<
"No vehicle available";
55 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Requesting message" << _messageId
56 <<
"attempt" << (_retryCount + 1) <<
"of" << (_maxRetries + 1);
58 _requestActive =
true;
60 [](
void* resultHandlerData,
65 if (!self->_requestActive) {
68 self->_handleResult(result, failureCode, message);
76void RetryableRequestMessageState::_queueRetry()
80 QMetaObject::invokeMethod(
this, [
this]() {
81 if (!_requestActive) {
85 }, Qt::QueuedConnection);
88void RetryableRequestMessageState::_handleResult(
100 _lastResult = result;
101 _lastFailureCode = effectiveFailureCode;
105 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Message received successfully";
107 if (_messageHandler) {
108 _messageHandler(
vehicle(), message);
116 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Request failed, failureCode:" << effectiveFailureCode;
118 if (_retryCount < _maxRetries) {
120 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Retrying, attempt" << (_retryCount + 1);
124 qCWarning(QGCStateMachineLog) <<
stateName() <<
"Max retries exhausted";
126 if (_failureHandler) {
127 _failureHandler(effectiveFailureCode, result);
131 if (_failOnMaxRetries) {
141 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Timeout waiting for message";
145 if (_retryCount < _maxRetries) {
147 qCDebug(QGCStateMachineLog) <<
stateName() <<
"Retrying after timeout, attempt" << (_retryCount + 1);
150 qCWarning(QGCStateMachineLog) <<
stateName() <<
"Max retries exhausted after timeout";
152 if (_failureHandler) {
153 _failureHandler(_lastFailureCode, _lastResult);
157 if (_failOnMaxRetries) {
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
@ RequestMessageFailureMessageNotReceived
@ RequestMessageNoFailure
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
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)
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.