3#include <QtCore/QTimer>
24 _responseCheckTimer.setSingleShot(
false);
25 _responseCheckTimer.setInterval(_responseCheckIntervalMSecs());
26 _responseCheckTimer.start();
27 connect(&_responseCheckTimer, &QTimer::timeout,
this, &MavCommandQueue::_responseTimeoutCheck);
32 _responseCheckTimer.stop();
33 _responseCheckTimer.disconnect();
38 qCDebug(MavCommandQueueLog) <<
"stop - clearing pending commands and halting response timer";
40 _responseCheckTimer.stop();
41 _responseCheckTimer.disconnect();
45void MavCommandQueue::sendCommand(
int compId, MAV_CMD command,
bool showError,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
53 param1, param2, param3, param4, param5, param6, param7);
56void MavCommandQueue::sendCommandDelayed(
int compId, MAV_CMD command,
bool showError,
int milliseconds,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
58 QTimer::singleShot(milliseconds,
this, [=,
this] {
59 sendCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
63void MavCommandQueue::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)
71 param1, param2, param3, param4, param5, param6, param7);
82 param1, param2, param3, param4, param5, param6, param7);
85void MavCommandQueue::sendCommandIntWithHandler(
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)
93 param1, param2, param3, param4, param5, param6, param7);
98struct LambdaFallbackHandlerData {
101 std::function<void()> unsupportedLambda;
106 auto* data =
static_cast<LambdaFallbackHandlerData*
>(resultHandlerData);
109 switch (ack.result) {
110 case MAV_RESULT_ACCEPTED:
113 case MAV_RESULT_UNSUPPORTED:
115 data->unsupportedLambda();
118 if (data->showError) {
129void MavCommandQueue::sendCommandWithLambdaFallback(std::function<
void()> lambda,
int compId, MAV_CMD command,
bool showError,
float param1,
float param2,
float param3,
float param4,
float param5,
float param6,
float param7)
133 switch (instanceData->getCommandSupported(command)) {
138 sendCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
141 auto* data =
new LambdaFallbackHandlerData { _vehicle, showError, std::move(lambda) };
143 &lambdaFallbackResultHandler,
148 sendCommandWithHandler(&handlerInfo, compId, command, param1, param2, param3, param4, param5, param6, param7);
161 for (
int i = 0; i < _list.count(); i++) {
162 const MavCommandListEntry_t& entry = _list[i];
163 if (entry.targetCompId == targetCompId && entry.command == command) {
170int MavCommandQueue::_responseCheckIntervalMSecs()
176int MavCommandQueue::_ackTimeoutMSecs()
182bool MavCommandQueue::_shouldRetry(MAV_CMD command)
202 case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
203 case MAV_CMD_REQUEST_MESSAGE:
204 case MAV_CMD_PREFLIGHT_STORAGE:
205 case MAV_CMD_RUN_PREARM_CHECKS:
213bool MavCommandQueue::_canBeDuplicated(MAV_CMD command)
219 case MAV_CMD_DO_MOTOR_TEST:
220 case MAV_CMD_SET_MESSAGE_INTERVAL:
227QString MavCommandQueue::_formatCommand(MAV_CMD command,
float param1)
231 QString commandStr = friendlyName.isEmpty() ? rawName : QStringLiteral(
"%1 (%2)").arg(friendlyName, rawName);
233 if (command == MAV_CMD_REQUEST_MESSAGE) {
234 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(
static_cast<int>(param1));
236 commandStr += QStringLiteral(
" [%1]").arg(info->name);
245 int targetCompId, MAV_CMD command, MAV_FRAME frame,
246 float param1,
float param2,
float param3,
float param4,
double param5,
double param6,
float param7)
256 if ((targetCompId == MAV_COMP_ID_ALL) || (
isPending(targetCompId, command) && !_canBeDuplicated(command))) {
257 bool compIdAll = targetCompId == MAV_COMP_ID_ALL;
260 qCDebug(MavCommandQueueLog) << QStringLiteral(
"sendWorker failing %1").arg(compIdAll ?
"MAV_COMP_ID_ALL not supported" :
"duplicate command") << rawCommandName << param1 << param2 << param3 << param4 << param5 << param6 << param7;
265 ack.result = MAV_RESULT_FAILED;
268 emit
commandResult(_vehicle->
id(), targetCompId, command, MAV_RESULT_FAILED, failureCode);
271 QGC::showAppMessage(tr(
"Unable to send command: %1.").arg(compIdAll ? tr(
"Internal error - MAV_COMP_ID_ALL not supported") : tr(
"Waiting on previous response to same command.")));
278 qCDebug(MavCommandQueueLog) <<
"sendWorker: primary link gone!";
283 ack.command = command;
284 ack.result = MAV_RESULT_FAILED;
287 emit
commandResult(_vehicle->
id(), targetCompId, command, MAV_RESULT_FAILED, failureCode);
296 MavCommandListEntry_t entry;
297 entry.useCommandInt = commandInt;
298 entry.targetCompId = targetCompId;
299 entry.command = command;
301 entry.showError = showError;
302 entry.ackHandlerInfo = {};
303 if (ackHandlerInfo) {
304 entry.ackHandlerInfo = *ackHandlerInfo;
306 entry.rgParam1 = param1;
307 entry.rgParam2 = param2;
308 entry.rgParam3 = param3;
309 entry.rgParam4 = param4;
310 entry.rgParam5 = param5;
311 entry.rgParam6 = param6;
312 entry.rgParam7 = param7;
314 entry.ackTimeoutMSecs = sharedLink->linkConfiguration()->isHighLatency() ? _ackTimeoutMSecsHighLatency : _ackTimeoutMSecs();
315 entry.elapsedTimer.start();
317 qCDebug(MavCommandQueueLog) <<
"Sending" << _formatCommand(command, param1) <<
"param1-7:" << command << param1 << param2 << param3 << param4 << param5 << param6 << param7;
320 _sendFromList(_list.count() - 1);
323void MavCommandQueue::_sendFromList(
int index)
325 MavCommandListEntry_t commandEntry = _list[index];
330 if (++_list[index].tryCount > commandEntry.maxTries) {
331 QString logMsg = QStringLiteral(
"Giving up sending command after max retries: %1").arg(rawCommandName);
334 if (commandEntry.command == MAV_CMD_REQUEST_MESSAGE) {
335 int requestedMsgId =
static_cast<int>(commandEntry.rgParam1);
336 const mavlink_message_info_t *info = mavlink_get_message_info_by_id(requestedMsgId);
337 logMsg += QStringLiteral(
" requesting: %1").arg(info ? info->name : QString::number(requestedMsgId));
340 qCWarning(MavCommandQueueLog) << logMsg;
342 _list.removeAt(index);
343 if (commandEntry.ackHandlerInfo.resultHandler) {
345 ack.result = MAV_RESULT_FAILED;
350 if (commandEntry.showError) {
356 if (commandEntry.tryCount > 1 && !_vehicle->
px4Firmware() && commandEntry.command == MAV_CMD_START_RX_PAIR) {
362 qCDebug(MavCommandQueueLog) <<
"Sending" << _formatCommand(commandEntry.command, commandEntry.rgParam1)
363 <<
"tryCount:param1-7" << commandEntry.tryCount << commandEntry.rgParam1 << commandEntry.rgParam2 << commandEntry.rgParam3 << commandEntry.rgParam4 << commandEntry.rgParam5 << commandEntry.rgParam6 << commandEntry.rgParam7;
367 qCDebug(MavCommandQueueLog) <<
"_sendFromList: primary link gone!";
373 if (commandEntry.useCommandInt) {
374 mavlink_command_int_t cmd;
375 memset(&cmd, 0,
sizeof(cmd));
376 cmd.target_system = _vehicle->
id();
377 cmd.target_component = commandEntry.targetCompId;
378 cmd.command = commandEntry.command;
379 cmd.frame = commandEntry.frame;
380 cmd.param1 = commandEntry.rgParam1;
381 cmd.param2 = commandEntry.rgParam2;
382 cmd.param3 = commandEntry.rgParam3;
383 cmd.param4 = commandEntry.rgParam4;
384 cmd.x = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam5 : commandEntry.rgParam5 * 1e7;
385 cmd.y = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam6 : commandEntry.rgParam6 * 1e7;
386 cmd.z = commandEntry.rgParam7;
389 sharedLink->mavlinkChannel(),
394 memset(&cmd, 0,
sizeof(cmd));
395 cmd.target_system = _vehicle->
id();
396 cmd.target_component = commandEntry.targetCompId;
397 cmd.command = commandEntry.command;
399 cmd.confirmation =
static_cast<uint8_t
>(qMin(commandEntry.tryCount - 1, 255));
400 cmd.param1 = commandEntry.rgParam1;
401 cmd.param2 = commandEntry.rgParam2;
402 cmd.param3 = commandEntry.rgParam3;
403 cmd.param4 = commandEntry.rgParam4;
404 cmd.param5 =
static_cast<float>(commandEntry.rgParam5);
405 cmd.param6 =
static_cast<float>(commandEntry.rgParam6);
406 cmd.param7 = commandEntry.rgParam7;
409 sharedLink->mavlinkChannel(),
417void MavCommandQueue::_responseTimeoutCheck()
419 if (_list.isEmpty()) {
424 for (
int i = _list.count() - 1; i >= 0; i--) {
425 MavCommandListEntry_t& commandEntry = _list[i];
426 if (commandEntry.elapsedTimer.elapsed() > commandEntry.ackTimeoutMSecs) {
437 QString commandStr = friendlyName.isEmpty() ? rawName : QStringLiteral(
"%1 (%2)").arg(friendlyName, rawName);
439 switch (ack.result) {
440 case MAV_RESULT_TEMPORARILY_REJECTED:
443 case MAV_RESULT_DENIED:
446 case MAV_RESULT_UNSUPPORTED:
449 case MAV_RESULT_FAILED:
460 int entryIndex =
findEntryIndex(message.compid,
static_cast<MAV_CMD
>(ack.command));
461 if (entryIndex == -1) {
463 qCDebug(MavCommandQueueLog) <<
"handleCommandAck Ack not in list" << rawCommandName;
467 if (ack.result == MAV_RESULT_IN_PROGRESS) {
468 MavCommandListEntry_t commandEntry;
469 if (_vehicle->
px4Firmware() && ack.command == MAV_CMD_DO_AUTOTUNE_ENABLE) {
471 commandEntry = _list.takeAt(entryIndex);
474 MavCommandListEntry_t& commandEntryRef = _list[entryIndex];
475 commandEntryRef.maxTries = 1;
476 commandEntryRef.elapsedTimer.start();
477 commandEntry = commandEntryRef;
480 if (commandEntry.ackHandlerInfo.progressHandler) {
481 (*commandEntry.ackHandlerInfo.progressHandler)(commandEntry.ackHandlerInfo.progressHandlerData, message.compid, ack);
486 MavCommandListEntry_t commandEntry = _list.takeAt(entryIndex);
487 if (commandEntry.ackHandlerInfo.resultHandler) {
488 (*commandEntry.ackHandlerInfo.resultHandler)(commandEntry.ackHandlerInfo.resultHandlerData, message.compid, ack,
MavCmdResultCommandResultOnly);
490 if (commandEntry.showError) {
499 switch (failureCode) {
501 return QStringLiteral(
"Command Result Only");
503 return QStringLiteral(
"No Response To Command");
505 return QStringLiteral(
"Duplicate Command");
507 return QStringLiteral(
"Unknown (%1)").arg(failureCode);
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
struct __mavlink_command_long_t mavlink_command_long_t
void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status)
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
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)
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)
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
QString friendlyName(MAV_CMD command) const
Returns the friendly name for the specified command.
static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED
static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED
static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED
static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED
static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
bool runningUnitTests()
True if the app is running in unit-test mode. Returns false if qgcApp() doesn't exist yet.
void showAppMessage(const QString &message, const QString &title)
Show a modal application message. Queued if the UI isn't ready yet.
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
MavCmdResultFailureCode_t
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.