|
QGroundControl
Ground Control Station for MAVLink Drones
|
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) | |
| 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 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.
| using WaitForParamResponseState::Predicate = std::function<bool(const mavlink_message_t &message)> |
Definition at line 23 of file WaitForParamResponseState.h.
| WaitForParamResponseState::WaitForParamResponseState | ( | QState * | parent, |
| int | timeoutMsecs, | ||
| Predicate | paramValuePredicate, | ||
| Predicate | paramErrorPredicate | ||
| ) |
| parent | Parent state |
| timeoutMsecs | Timeout in milliseconds to wait for response, 0 to wait forever |
| paramValuePredicate | Predicate to filter PARAM_VALUE messages |
| paramErrorPredicate | Predicate to filter PARAM_ERROR messages |
Definition at line 7 of file WaitForParamResponseState.cc.
|
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().
|
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().
|
inline |
Definition at line 34 of file WaitForParamResponseState.h.
|
inline |
Definition at line 37 of file WaitForParamResponseState.h.