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

#include <RequestMessageState.h>

+ Inheritance diagram for RequestMessageState:
+ Collaboration diagram for RequestMessageState:

Public Types

using MessageHandler = std::function< void(Vehicle *vehicle, const mavlink_message_t &message)>
 
- 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 the message is successfully received.
 
- Signals inherited from WaitStateBase
void completed ()
 
void timeout ()
 
void timedOut ()
 
- Signals inherited from QGCAbstractState
void advance ()
 
void error ()
 

Public Member Functions

 RequestMessageState (QState *parent, uint32_t messageId, MessageHandler messageHandler=MessageHandler(), int compId=MAV_COMP_ID_AUTOPILOT1, int timeoutMsecs=5000, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
 
Vehicle::RequestMessageResultHandlerFailureCode_t failureCode () const
 
MAV_RESULT commandResult () const
 
- 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 onWaitTimeout () override
 Called when the timeout expires - default emits timeout(), subclasses can override.
 
- Protected Member Functions inherited from WaitStateBase
virtual void onWaitExited ()
 Called when the state is exited - subclasses should call base implementation.
 
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 from the vehicle using MAV_CMD_REQUEST_MESSAGE. Emits messageReceived() with the decoded message on success. Emits completed()/advance() on success, timeout()/timedOut() on timeout, error() on failure.

Note: Vehicle::requestMessage() has its own internal timeout, but this state adds an additional safety timeout at the state machine level.

Definition at line 15 of file RequestMessageState.h.

Member Typedef Documentation

◆ MessageHandler

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

Definition at line 21 of file RequestMessageState.h.

Constructor & Destructor Documentation

◆ RequestMessageState()

RequestMessageState::RequestMessageState ( QState *  parent,
uint32_t  messageId,
MessageHandler  messageHandler = MessageHandler(),
int  compId = MAV_COMP_ID_AUTOPILOT1,
int  timeoutMsecs = 5000,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
float  param5 = 0.0f 
)
Parameters
parentParent state
messageIdMAVLink message ID to request
messageHandlerOptional handler called with the received message before advance() is emitted
compIdComponent ID to request from (default: MAV_COMP_ID_AUTOPILOT1)
timeoutMsecsTimeout in milliseconds (default: 5000, 0 = no timeout)
param1-param5Optional parameters for the request

Definition at line 5 of file RequestMessageState.cc.

Member Function Documentation

◆ commandResult()

MAV_RESULT RequestMessageState::commandResult ( ) const
inline
Returns
The MAV_RESULT from the last request attempt

Definition at line 44 of file RequestMessageState.h.

◆ connectWaitSignal()

void RequestMessageState::connectWaitSignal ( )
inlineoverrideprotectedvirtual

Subclasses override to set up their signal connections.

Implements WaitStateBase.

Definition at line 51 of file RequestMessageState.h.

◆ disconnectWaitSignal()

void RequestMessageState::disconnectWaitSignal ( )
inlineoverrideprotectedvirtual

Subclasses override to tear down their signal connections.

Implements WaitStateBase.

Definition at line 52 of file RequestMessageState.h.

◆ failureCode()

Vehicle::RequestMessageResultHandlerFailureCode_t RequestMessageState::failureCode ( ) const
inline
Returns
The failure code from the last request attempt

Definition at line 41 of file RequestMessageState.h.

◆ messageReceived

void RequestMessageState::messageReceived ( const mavlink_message_t message)
signal

Emitted when the message is successfully received.

◆ onWaitEntered()

void RequestMessageState::onWaitEntered ( )
overrideprotectedvirtual

◆ onWaitTimeout()

void RequestMessageState::onWaitTimeout ( )
overrideprotectedvirtual

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

Reimplemented from WaitStateBase.

Definition at line 51 of file RequestMessageState.cc.

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


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