5#include <QtCore/QElapsedTimer>
7#include <QtCore/QObject>
8#include <QtCore/QTimer>
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);
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);
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);
42 int compId, MAV_CMD command, MAV_FRAME frame,
43 float param1,
float param2,
float param3,
float param4,
double param5,
double param6,
float param7);
46 bool isPending(
int targetCompId, MAV_CMD command)
const;
68 void commandResult(
int vehicleId,
int targetComponent,
int command,
int ackResult,
int failureCode);
71 void _responseTimeoutCheck();
74 typedef struct MavCommandListEntry {
76 bool useCommandInt =
false;
86 bool showError =
true;
90 QElapsedTimer elapsedTimer;
91 int ackTimeoutMSecs = 0;
92 } MavCommandListEntry_t;
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);
102 QList<MavCommandListEntry_t> _list;
103 QTimer _responseCheckTimer;
104 bool _stopped =
false;
106 static constexpr int _ackTimeoutMSecsHighLatency = 120000;
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.
MavCmdResultFailureCode_t