QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RequestMessageCoordinator.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QElapsedTimer>
4#include <QtCore/QList>
5#include <QtCore/QMap>
6#include <QtCore/QObject>
7#include <QtCore/QPointer>
8
9#include "VehicleTypes.h"
10
11class MavCommandQueue;
12class Vehicle;
13
18class RequestMessageCoordinator : public QObject, public VehicleTypes
19{
20 Q_OBJECT
21
22public:
23 RequestMessageCoordinator(Vehicle* vehicle, MavCommandQueue* commandQueue);
25
29 void requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData,
30 int compId, int messageId,
31 float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f);
32
35 void handleReceivedMessage(const mavlink_message_t& message);
36
38 void stop();
39
41
42private:
43 typedef struct RequestMessageInfo {
44 QPointer<Vehicle> vehicle; // QPointer automatically becomes null when Vehicle is destroyed
45 RequestMessageCoordinator* coordinator = nullptr; // Back-pointer so the static ack handler can reach the instance.
46 int compId = 0;
47 int msgId = 0;
48 float param1 = 0.0f;
49 float param2 = 0.0f;
50 float param3 = 0.0f;
51 float param4 = 0.0f;
52 float param5 = 0.0f;
53 RequestMessageResultHandler resultHandler = nullptr;
54 void* resultHandlerData = nullptr;
55 bool commandAckReceived = false; // We keep track of the ack/message being received since the order in which this will come in is random
56 bool messageReceived = false; // We only delete the allocated RequestMessageInfo when both the message is received and we get the ack
57 QElapsedTimer messageWaitElapsedTimer; // Elapsed time since we started waiting message to show up
58 mavlink_message_t message;
59 } RequestMessageInfo_t;
60
61 void _removeInfo(int compId, int msgId);
62 bool _duplicate(int compId, int msgId) const;
63 void _sendNow(RequestMessageInfo_t* info);
64 void _sendNextFromQueue(int compId);
65
66 static void _cmdResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode);
67
68 Vehicle* _vehicle = nullptr;
69 MavCommandQueue* _commandQueue = nullptr;
70
71 QMap<int /* compId */, QMap<int /* msgId */, RequestMessageInfo_t*>> _infoMap; // Active requests awaiting response
72 QMap<int /* compId */, QList<RequestMessageInfo_t*>> _queueMap; // Per-component queue waiting for active request to finish
73};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_ack_t mavlink_command_ack_t
void handleReceivedMessage(const mavlink_message_t &message)
static QString failureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
void stop()
Clear pending state without firing callbacks (used during vehicle shutdown).
void(* RequestMessageResultHandler)(void *resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message)
Callback for requestMessage — delivered when the ack/message pair resolves or a failure occurs.
RequestMessageResultHandlerFailureCode_t