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"
5
6#include <cstdint>
7#include <functional>
8
9class Vehicle;
10
16{
17 Q_OBJECT
18 Q_DISABLE_COPY(WaitForMavlinkMessageState)
19
20public:
21 using Predicate = std::function<bool(const mavlink_message_t &message)>;
22
27 WaitForMavlinkMessageState(QState *parent, uint32_t messageId, int timeoutMsecs, Predicate predicate = Predicate());
28
30 uint32_t messageId() const { return _messageId; }
31
32protected:
33 void connectWaitSignal() override;
34 void disconnectWaitSignal() override;
35
36private slots:
37 void _messageReceived(const mavlink_message_t &message);
38
39private:
40 uint32_t _messageId = 0U;
41 Predicate _predicate;
42};
struct __mavlink_message mavlink_message_t
Waits for the specified MAVLink message from the vehicle.
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
Base class for states that wait for something with optional timeout.
int timeoutMsecs() const