QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RequestMessageState.h
Go to the documentation of this file.
1#pragma once
2
3#include "WaitStateBase.h"
4#include "Vehicle.h"
5
6#include <cstdint>
7#include <functional>
8
16{
17 Q_OBJECT
18 Q_DISABLE_COPY(RequestMessageState)
19
20public:
21 using MessageHandler = std::function<void(Vehicle* vehicle, const mavlink_message_t& message)>;
22
29 RequestMessageState(QState* parent,
30 uint32_t messageId,
31 MessageHandler messageHandler = MessageHandler(),
32 int compId = MAV_COMP_ID_AUTOPILOT1,
33 int timeoutMsecs = 5000,
34 float param1 = 0.0f,
35 float param2 = 0.0f,
36 float param3 = 0.0f,
37 float param4 = 0.0f,
38 float param5 = 0.0f);
39
42
44 MAV_RESULT commandResult() const { return _commandResult; }
45
46signals:
48 void messageReceived(const mavlink_message_t& message);
49
50protected:
51 void connectWaitSignal() override {}
52 void disconnectWaitSignal() override {}
53 void onWaitEntered() override;
54 void onWaitTimeout() override;
55
56private:
57 static void _resultHandler(void* resultHandlerData,
58 MAV_RESULT commandResult,
60 const mavlink_message_t& message);
61
62 uint32_t _messageId;
63 MessageHandler _messageHandler;
64 int _compId;
65 float _param1;
66 float _param2;
67 float _param3;
68 float _param4;
69 float _param5;
70
72 MAV_RESULT _commandResult = MAV_RESULT_ACCEPTED;
73};
struct __mavlink_message mavlink_message_t
Vehicle * vehicle() const
void onWaitEntered() override
Called when the state is entered - subclasses should call base implementation.
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
void connectWaitSignal() override
Subclasses override to set up their signal connections.
MAV_RESULT commandResult() const
Vehicle::RequestMessageResultHandlerFailureCode_t failureCode() const
std::function< void(Vehicle *vehicle, const mavlink_message_t &message)> MessageHandler
void onWaitTimeout() override
Called when the timeout expires - default emits timeout(), subclasses can override.
void messageReceived(const mavlink_message_t &message)
Emitted when the message is successfully received.
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageNoFailure
Definition Vehicle.h:669
int timeoutMsecs() const