|
QGroundControl
Ground Control Station for MAVLink Drones
|
#include <WaitForMavlinkMessageState.h>
Inheritance diagram for WaitForMavlinkMessageState:
Collaboration diagram for WaitForMavlinkMessageState: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 | |
| WaitForMavlinkMessageState (QState *parent, uint32_t messageId, int timeoutMsecs, Predicate predicate=Predicate()) | |
| uint32_t | messageId () 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) | |
| QGCStateMachine * | machine () const |
| Vehicle * | vehicle () const |
| QString | stateName () const |
| class StateContext * | context () 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 () |
Waits for the specified MAVLink message from the vehicle Filters by message ID and optional predicate before advancing
Definition at line 13 of file WaitForMavlinkMessageState.h.
| using WaitForMavlinkMessageState::Predicate = std::function<bool(const mavlink_message_t &message)> |
Definition at line 19 of file WaitForMavlinkMessageState.h.
| WaitForMavlinkMessageState::WaitForMavlinkMessageState | ( | QState * | parent, |
| uint32_t | messageId, | ||
| int | timeoutMsecs, | ||
| Predicate | predicate = Predicate() |
||
| ) |
| parent | Parent state |
| messageId | MAVLink message ID to wait for |
| timeoutMsecs | Timeout in milliseconds to wait for message, 0 to wait forever |
| predicate | Optional predicate which further filters received messages |
Definition at line 7 of file WaitForMavlinkMessageState.cc.
|
overrideprotectedvirtual |
Subclasses override to set up their signal connections.
Implements WaitStateBase.
Definition at line 14 of file WaitForMavlinkMessageState.cc.
References Vehicle::mavlinkMessageReceived(), and QGCAbstractState::vehicle().
|
overrideprotectedvirtual |
Subclasses override to tear down their signal connections.
Implements WaitStateBase.
Definition at line 19 of file WaitForMavlinkMessageState.cc.
References Vehicle::mavlinkMessageReceived(), and QGCAbstractState::vehicle().
|
inline |
Definition at line 28 of file WaitForMavlinkMessageState.h.