QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
WaitForMavlinkMessageState.h
Go to the documentation of this file.
1#pragma once
2
3#include "WaitStateBase.h"
4#include "QGCMAVLink.h"
5
6#include <cstdint>
7#include <functional>
8
9class Vehicle;
10
14{
15 Q_OBJECT
16 Q_DISABLE_COPY(WaitForMavlinkMessageState)
17
18public:
19 using Predicate = std::function<bool(const mavlink_message_t &message)>;
20
25 WaitForMavlinkMessageState(QState *parent, uint32_t messageId, int timeoutMsecs, Predicate predicate = Predicate());
26
28 uint32_t messageId() const { return _messageId; }
29
30protected:
31 void connectWaitSignal() override;
32 void disconnectWaitSignal() override;
33
34private slots:
35 void _messageReceived(const mavlink_message_t &message);
36
37private:
38 uint32_t _messageId = 0U;
39 Predicate _predicate;
40};
struct __mavlink_message mavlink_message_t
void connectWaitSignal() override
Subclasses override to set up their signal connections.
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
std::function< bool(const mavlink_message_t &message)> Predicate
int timeoutMsecs() const