QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RetryableRequestMessageState Class Reference

#include <RetryableRequestMessageState.h>

+ Inheritance diagram for RetryableRequestMessageState:
+ Collaboration diagram for RetryableRequestMessageState:

Public Types

using MessageHandler = std::function< void(Vehicle *vehicle, const mavlink_message_t &message)>
 
using FailureHandler = std::function< void(Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)>
 
using SkipPredicate = std::function< bool()>
 
- Public Types inherited from QGCAbstractState
using EntryCallback = std::function< void()>
 
using ExitCallback = std::function< void()>
 
using EventHandler = std::function< bool(QEvent *)>
 

Signals

void messageReceived (const mavlink_message_t &message)
 Emitted when message is successfully received.
 
void retriesExhausted ()
 Emitted when all retries are exhausted.
 
- Signals inherited from WaitStateBase
void completed ()
 
void timeout ()
 
void timedOut ()
 
- Signals inherited from QGCAbstractState
void advance ()
 
void error ()
 

Public Member Functions

 RetryableRequestMessageState (const QString &stateName, QState *parent, uint32_t messageId, MessageHandler messageHandler=nullptr, int maxRetries=1, int compId=MAV_COMP_ID_AUTOPILOT1, int timeoutMsecs=5000)
 
void setFailureHandler (FailureHandler handler)
 Set handler called when all retries fail.
 
void setSkipPredicate (SkipPredicate predicate)
 
void setFailOnMaxRetries (bool fail)
 If true, emit error() after max retries instead of advance()
 
Vehicle::RequestMessageResultHandlerFailureCode_t lastFailureCode () const
 Get the failure code from the last attempt.
 
MAV_RESULT lastResult () const
 Get the MAV_RESULT from the last attempt.
 
int retryCount () const
 Get current retry count.
 
int maxRetries () const
 Get max retries setting.
 
- Public Member Functions inherited from WaitStateBase
 WaitStateBase (const QString &stateName, QState *parent, int timeoutMsecs=0)
 
void restartWait ()
 
- Public Member Functions inherited from QGCState
 QGCState (const QString &stateName, QState *parentState)
 
template<typename PointerToMemberFunction >
QSignalTransition * addThisTransition (PointerToMemberFunction signal, QAbstractState *target)
 Simpler version of QState::addTransition which assumes the sender is this.
 
void setLocalErrorState (QAbstractState *errorState)
 
QAbstractState * localErrorState () const
 Get the per-state error state (nullptr if using global)
 
void setProperty (QObject *object, const char *name, const QVariant &value)
 
void setEnabled (QObject *object, bool enabled)
 Convenience overload for setting enabled state on widgets/controls.
 
void setVisible (QObject *object, bool visible)
 Convenience overload for setting visible state on widgets/controls.
 
- Public Member Functions inherited from QGCAbstractState
 QGCAbstractState (const QString &stateName, QState *parent)
 
QGCStateMachinemachine () const
 
Vehiclevehicle () const
 
QString stateName () const
 
class StateContextcontext () const
 
void setOnEntry (EntryCallback callback)
 Set a callback to be invoked when the state is entered.
 
void setOnExit (ExitCallback callback)
 Set a callback to be invoked when the state is exited.
 
void setCallbacks (EntryCallback onEntry, ExitCallback onExit=nullptr)
 Set both entry and exit callbacks.
 
void setEventHandler (EventHandler handler)
 Set a custom event handler for this state.
 

Protected Member Functions

void connectWaitSignal () override
 Subclasses override to set up their signal connections.
 
void disconnectWaitSignal () override
 Subclasses override to tear down their signal connections.
 
void onWaitEntered () override
 Called when the state is entered - subclasses should call base implementation.
 
void onWaitExited () override
 Called when the state is exited - subclasses should call base implementation.
 
void onWaitTimeout () override
 Called when the timeout expires - default emits timeout(), subclasses can override.
 
- Protected Member Functions inherited from WaitStateBase
void waitComplete ()
 
void waitFailed ()
 
int timeoutMsecs () const
 
- Protected Member Functions inherited from QGCAbstractState
virtual void onEnter ()
 Override to perform actions on state entry.
 
virtual void onLeave ()
 Override to perform actions on state exit.
 
void onEntry (QEvent *event) override
 
void onExit (QEvent *event) override
 
bool event (QEvent *event) override
 

Detailed Description

Requests a MAVLink message with built-in retry logic. On failure, retries up to maxRetries times before giving up.

Emits advance() on success or after all retries exhausted. Emits error() only if explicitly requested via failOnMaxRetries.

Example usage:

auto* state = new RetryableRequestMessageState(
"GetVersion", &machine,
MAVLINK_MSG_ID_AUTOPILOT_VERSION,
[this](Vehicle* v, const mavlink_message_t& msg) {
// Handle successful message
},
2 // max retries
);
struct __mavlink_message mavlink_message_t
QGCStateMachine * machine() const

Definition at line 25 of file RetryableRequestMessageState.h.

Member Typedef Documentation

◆ FailureHandler

using RetryableRequestMessageState::FailureHandler = std::function<void(Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)>

Definition at line 32 of file RetryableRequestMessageState.h.

◆ MessageHandler

using RetryableRequestMessageState::MessageHandler = std::function<void(Vehicle* vehicle, const mavlink_message_t& message)>

Definition at line 31 of file RetryableRequestMessageState.h.

◆ SkipPredicate

using RetryableRequestMessageState::SkipPredicate = std::function<bool()>

Definition at line 33 of file RetryableRequestMessageState.h.

Constructor & Destructor Documentation

◆ RetryableRequestMessageState()

RetryableRequestMessageState::RetryableRequestMessageState ( const QString &  stateName,
QState *  parent,
uint32_t  messageId,
MessageHandler  messageHandler = nullptr,
int  maxRetries = 1,
int  compId = MAV_COMP_ID_AUTOPILOT1,
int  timeoutMsecs = 5000 
)

Create a retryable request message state

Parameters
stateNameName for this state
parentParent state
messageIdMAVLink message ID to request
messageHandlerHandler called on successful message receipt
maxRetriesMaximum retry attempts (default: 1)
compIdComponent ID to request from (default: MAV_COMP_ID_AUTOPILOT1)
timeoutMsecsTimeout per attempt in milliseconds (default: 5000)

Definition at line 9 of file RetryableRequestMessageState.cc.

Member Function Documentation

◆ connectWaitSignal()

void RetryableRequestMessageState::connectWaitSignal ( )
inlineoverrideprotectedvirtual

Subclasses override to set up their signal connections.

Implements WaitStateBase.

Definition at line 81 of file RetryableRequestMessageState.h.

◆ disconnectWaitSignal()

void RetryableRequestMessageState::disconnectWaitSignal ( )
inlineoverrideprotectedvirtual

Subclasses override to tear down their signal connections.

Implements WaitStateBase.

Definition at line 82 of file RetryableRequestMessageState.h.

◆ lastFailureCode()

Vehicle::RequestMessageResultHandlerFailureCode_t RetryableRequestMessageState::lastFailureCode ( ) const
inline

Get the failure code from the last attempt.

Definition at line 62 of file RetryableRequestMessageState.h.

◆ lastResult()

MAV_RESULT RetryableRequestMessageState::lastResult ( ) const
inline

Get the MAV_RESULT from the last attempt.

Definition at line 65 of file RetryableRequestMessageState.h.

◆ maxRetries()

int RetryableRequestMessageState::maxRetries ( ) const
inline

Get max retries setting.

Definition at line 71 of file RetryableRequestMessageState.h.

◆ messageReceived

void RetryableRequestMessageState::messageReceived ( const mavlink_message_t message)
signal

Emitted when message is successfully received.

◆ onWaitEntered()

void RetryableRequestMessageState::onWaitEntered ( )
overrideprotectedvirtual

Called when the state is entered - subclasses should call base implementation.

Reimplemented from WaitStateBase.

Definition at line 25 of file RetryableRequestMessageState.cc.

References WaitStateBase::onWaitEntered(), QGCAbstractState::stateName(), and WaitStateBase::waitComplete().

◆ onWaitExited()

void RetryableRequestMessageState::onWaitExited ( )
overrideprotectedvirtual

Called when the state is exited - subclasses should call base implementation.

Reimplemented from WaitStateBase.

Definition at line 40 of file RetryableRequestMessageState.cc.

References WaitStateBase::onWaitExited().

◆ onWaitTimeout()

void RetryableRequestMessageState::onWaitTimeout ( )
overrideprotectedvirtual

Called when the timeout expires - default emits timeout(), subclasses can override.

Reimplemented from WaitStateBase.

Definition at line 139 of file RetryableRequestMessageState.cc.

References WaitStateBase::onWaitTimeout(), Vehicle::RequestMessageFailureMessageNotReceived, retriesExhausted(), QGCAbstractState::stateName(), and WaitStateBase::waitComplete().

◆ retriesExhausted

void RetryableRequestMessageState::retriesExhausted ( )
signal

Emitted when all retries are exhausted.

Referenced by onWaitTimeout().

◆ retryCount()

int RetryableRequestMessageState::retryCount ( ) const
inline

Get current retry count.

Definition at line 68 of file RetryableRequestMessageState.h.

◆ setFailOnMaxRetries()

void RetryableRequestMessageState::setFailOnMaxRetries ( bool  fail)
inline

If true, emit error() after max retries instead of advance()

Definition at line 59 of file RetryableRequestMessageState.h.

◆ setFailureHandler()

void RetryableRequestMessageState::setFailureHandler ( FailureHandler  handler)
inline

Set handler called when all retries fail.

Definition at line 52 of file RetryableRequestMessageState.h.

◆ setSkipPredicate()

void RetryableRequestMessageState::setSkipPredicate ( SkipPredicate  predicate)
inline

Set predicate to check if request should be skipped If predicate returns true, state completes immediately without sending request

Definition at line 56 of file RetryableRequestMessageState.h.


The documentation for this class was generated from the following files: