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

Waits for either PARAM_VALUE (success) or PARAM_ERROR (rejection) from the vehicle. More...

#include <WaitForParamResponseState.h>

+ Inheritance diagram for WaitForParamResponseState:
+ Collaboration diagram for WaitForParamResponseState:

Public Types

using Predicate = std::function< bool(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 *)>
 

Public Member Functions

 WaitForParamResponseState (QState *parent, int timeoutMsecs, Predicate paramValuePredicate, Predicate paramErrorPredicate)
 
uint8_t lastParamError () const
 
QString lastParamErrorString () 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.
 
- Protected Member Functions inherited from WaitStateBase
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.
 
virtual void onWaitTimeout ()
 Called when the timeout expires - default emits timeout(), subclasses can override.
 
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
 

Additional Inherited Members

- Signals inherited from WaitStateBase
void completed ()
 
void timeout ()
 
void timedOut ()
 
- Signals inherited from QGCAbstractState
void advance ()
 
void error ()
 

Detailed Description

Waits for either PARAM_VALUE (success) or PARAM_ERROR (rejection) from the vehicle.

On PARAM_VALUE matching predicate: calls waitComplete() (emits advance()) On PARAM_ERROR matching predicate: stores error info, calls waitFailed() (emits error()) On timeout: existing timeout() signal fires (for retry path)

Definition at line 17 of file WaitForParamResponseState.h.

Member Typedef Documentation

◆ Predicate

using WaitForParamResponseState::Predicate = std::function<bool(const mavlink_message_t &message)>

Definition at line 23 of file WaitForParamResponseState.h.

Constructor & Destructor Documentation

◆ WaitForParamResponseState()

WaitForParamResponseState::WaitForParamResponseState ( QState *  parent,
int  timeoutMsecs,
Predicate  paramValuePredicate,
Predicate  paramErrorPredicate 
)
Parameters
parentParent state
timeoutMsecsTimeout in milliseconds to wait for response, 0 to wait forever
paramValuePredicatePredicate to filter PARAM_VALUE messages
paramErrorPredicatePredicate to filter PARAM_ERROR messages

Definition at line 7 of file WaitForParamResponseState.cc.

Member Function Documentation

◆ connectWaitSignal()

void WaitForParamResponseState::connectWaitSignal ( )
overrideprotectedvirtual

Subclasses override to set up their signal connections.

Implements WaitStateBase.

Definition at line 16 of file WaitForParamResponseState.cc.

References Vehicle::mavlinkMessageReceived(), and QGCAbstractState::vehicle().

◆ disconnectWaitSignal()

void WaitForParamResponseState::disconnectWaitSignal ( )
overrideprotectedvirtual

Subclasses override to tear down their signal connections.

Implements WaitStateBase.

Definition at line 21 of file WaitForParamResponseState.cc.

References Vehicle::mavlinkMessageReceived(), and QGCAbstractState::vehicle().

◆ lastParamError()

uint8_t WaitForParamResponseState::lastParamError ( ) const
inline
Returns
The last PARAM_ERROR error code received

Definition at line 34 of file WaitForParamResponseState.h.

◆ lastParamErrorString()

QString WaitForParamResponseState::lastParamErrorString ( ) const
inline
Returns
Human-readable string for the last PARAM_ERROR received

Definition at line 37 of file WaitForParamResponseState.h.


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