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 "MAVLinkEnums.h"
6#include "VehicleTypes.h"
7
8class Vehicle;
9
10#include <cstdint>
11#include <functional>
12
22{
23 Q_OBJECT
24 Q_DISABLE_COPY(RequestMessageState)
25
26public:
27 using MessageHandler = std::function<void(Vehicle* vehicle, const mavlink_message_t& message)>;
28
35 RequestMessageState(QState* parent,
36 uint32_t messageId,
37 MessageHandler messageHandler = MessageHandler(),
38 int compId = MAV_COMP_ID_AUTOPILOT1,
39 int timeoutMsecs = 5000,
40 float param1 = 0.0f,
41 float param2 = 0.0f,
42 float param3 = 0.0f,
43 float param4 = 0.0f,
44 float param5 = 0.0f);
45
48
50 MAV_RESULT commandResult() const { return _commandResult; }
51
52signals:
54 void messageReceived(const mavlink_message_t& message);
55
56protected:
57 void connectWaitSignal() override {}
58 void disconnectWaitSignal() override {}
59 void onWaitEntered() override;
60 void onWaitTimeout() override;
61
62private:
63 static void _resultHandler(void* resultHandlerData,
64 MAV_RESULT commandResult,
66 const mavlink_message_t& message);
67
68 uint32_t _messageId;
69 MessageHandler _messageHandler;
70 int _compId;
71 float _param1;
72 float _param2;
73 float _param3;
74 float _param4;
75 float _param5;
76
78 MAV_RESULT _commandResult = MAV_RESULT_ACCEPTED;
79};
struct __mavlink_message mavlink_message_t
Vehicle * vehicle() const
Requests a MAVLink message from the vehicle using MAV_CMD_REQUEST_MESSAGE.
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
VehicleTypes::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.
Base class for states that wait for something with optional timeout.
int timeoutMsecs() const
RequestMessageResultHandlerFailureCode_t
@ RequestMessageNoFailure