QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
WaitForMavlinkMessageState.cc
Go to the documentation of this file.
2#include "Vehicle.h"
4
5#include <utility>
6
7WaitForMavlinkMessageState::WaitForMavlinkMessageState(QState *parent, uint32_t messageId, int timeoutMsecs, Predicate predicate)
8 : WaitStateBase(QStringLiteral("WaitForMavlinkMessageState:%1").arg(messageId), parent, timeoutMsecs)
9 , _messageId(messageId)
10 , _predicate(std::move(predicate))
11{
12}
13
15{
16 connect(vehicle(), &Vehicle::mavlinkMessageReceived, this, &WaitForMavlinkMessageState::_messageReceived, Qt::UniqueConnection);
17}
18
20{
21 if (vehicle()) {
22 disconnect(vehicle(), &Vehicle::mavlinkMessageReceived, this, &WaitForMavlinkMessageState::_messageReceived);
23 }
24}
25
26void WaitForMavlinkMessageState::_messageReceived(const mavlink_message_t &message)
27{
28 if (message.msgid != _messageId) {
29 return;
30 }
31 if (_predicate && !_predicate(message)) {
32 return;
33 }
34
35 qCDebug(QGCStateMachineLog) << "Received expected message id" << _messageId << stateName();
37}
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
void mavlinkMessageReceived(const mavlink_message_t &message)
void connectWaitSignal() override
Subclasses override to set up their signal connections.
WaitForMavlinkMessageState(QState *parent, uint32_t messageId, int timeoutMsecs, Predicate predicate=Predicate())
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
std::function< bool(const mavlink_message_t &message)> Predicate