3#include <QtCore/QElapsedTimer>
6#include <QtCore/QObject>
7#include <QtCore/QPointer>
31 int compId,
int messageId,
32 float param1 = 0.0f,
float param2 = 0.0f,
float param3 = 0.0f,
float param4 = 0.0f,
float param5 = 0.0f);
44 typedef struct RequestMessageInfo {
45 QPointer<Vehicle> vehicle;
55 void* resultHandlerData =
nullptr;
56 bool commandAckReceived =
false;
57 bool messageReceived =
false;
58 QElapsedTimer messageWaitElapsedTimer;
60 } RequestMessageInfo_t;
62 void _removeInfo(
int compId,
int msgId);
63 bool _duplicate(
int compId,
int msgId)
const;
64 void _sendNow(RequestMessageInfo_t* info);
65 void _sendNextFromQueue(
int compId);
72 QMap<
int , QMap<
int , RequestMessageInfo_t*>> _infoMap;
73 QMap<
int , QList<RequestMessageInfo_t*>> _queueMap;
struct __mavlink_message mavlink_message_t
struct __mavlink_command_ack_t mavlink_command_ack_t
Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.
Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation,...
void handleReceivedMessage(const mavlink_message_t &message)
static QString failureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
~RequestMessageCoordinator()
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.
MavCmdResultFailureCode_t
RequestMessageResultHandlerFailureCode_t