QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MavCommandQueue.h
Go to the documentation of this file.
1#pragma once
2
3#include <functional>
4
5#include <QtCore/QElapsedTimer>
6#include <QtCore/QList>
7#include <QtCore/QObject>
8#include <QtCore/QTimer>
9
10#include "VehicleTypes.h"
11
12class Vehicle;
13
20class MavCommandQueue : public QObject, public VehicleTypes
21{
22 Q_OBJECT
23
24public:
25 explicit MavCommandQueue(Vehicle* vehicle);
27
28 // Public send API — mirrors Vehicle's historical sendMavCommand* surface.
29 void sendCommand (int compId, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
30 void sendCommandDelayed (int compId, MAV_CMD command, bool showError, int milliseconds, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
31 void sendCommandInt (int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
32
33 void sendCommandWithHandler (const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
34 void sendCommandIntWithHandler (const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, double param5 = 0.0, double param6 = 0.0, float param7 = 0.0f);
35
36 void sendCommandWithLambdaFallback(std::function<void()> lambda, int compId, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
37
41 void sendWorker(bool commandInt, bool showError, const MavCmdAckHandlerInfo_t* ackHandlerInfo,
42 int compId, MAV_CMD command, MAV_FRAME frame,
43 float param1, float param2, float param3, float param4, double param5, double param6, float param7);
44
46 bool isPending(int targetCompId, MAV_CMD command) const;
47
49 int findEntryIndex(int targetCompId, MAV_CMD command) const;
50
52 void handleCommandAck(const mavlink_message_t& message, const mavlink_command_ack_t& ack);
53
56 void stop();
57
58 static QString failureCodeToString(MavCmdResultFailureCode_t failureCode);
59 static void showCommandAckError(const mavlink_command_ack_t& ack);
60
61 // Test tuning knobs.
62 static constexpr int kTestAckTimeoutMs = 500;
63 static constexpr int kMaxRetryCount = 3;
64 static constexpr int kTestMaxWaitMs = kTestAckTimeoutMs * kMaxRetryCount * 2;
65
66signals:
68 void commandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode);
69
70private slots:
71 void _responseTimeoutCheck();
72
73private:
74 typedef struct MavCommandListEntry {
75 int targetCompId = 0;
76 bool useCommandInt = false;
77 MAV_CMD command;
78 MAV_FRAME frame;
79 float rgParam1 = 0;
80 float rgParam2 = 0;
81 float rgParam3 = 0;
82 float rgParam4 = 0;
83 double rgParam5 = 0;
84 double rgParam6 = 0;
85 float rgParam7 = 0;
86 bool showError = true;
87 MavCmdAckHandlerInfo_t ackHandlerInfo;
88 int maxTries = kMaxRetryCount;
89 int tryCount = 0;
90 QElapsedTimer elapsedTimer;
91 int ackTimeoutMSecs = 0;
92 } MavCommandListEntry_t;
93
94 void _sendFromList(int index);
95 static bool _shouldRetry(MAV_CMD command);
96 static bool _canBeDuplicated(MAV_CMD command);
97 static int _responseCheckIntervalMSecs();
98 static int _ackTimeoutMSecs();
99 static QString _formatCommand(MAV_CMD command, float param1);
100
101 Vehicle* _vehicle = nullptr;
102 QList<MavCommandListEntry_t> _list;
103 QTimer _responseCheckTimer;
104 bool _stopped = false; // set by stop(), gates all send paths
105
106 static constexpr int _ackTimeoutMSecsHighLatency = 120000;
107};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_ack_t mavlink_command_ack_t
void sendCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
static QString failureCodeToString(MavCmdResultFailureCode_t failureCode)
static constexpr int kTestAckTimeoutMs
void commandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
Emitted for every terminal ack that has no user-provided resultHandler.
void sendCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f)
static constexpr int kTestMaxWaitMs
void sendCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
static constexpr int kMaxRetryCount
void sendWorker(bool commandInt, bool showError, const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
void handleCommandAck(const mavlink_message_t &message, const mavlink_command_ack_t &ack)
Process a COMMAND_ACK — match it to a pending entry and fire callbacks.
void sendCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
bool isPending(int targetCompId, MAV_CMD command) const
True if a matching (targetCompId, command) is already queued or awaiting ack.
static void showCommandAckError(const mavlink_command_ack_t &ack)
void sendCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
int findEntryIndex(int targetCompId, MAV_CMD command) const
Index of a matching entry in the pending queue, or -1. Exposed for test use.
void sendCommandWithLambdaFallback(std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Callback info bundle for sendMavCommandWithHandler.