QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MavCommandQueue.cc
Go to the documentation of this file.
1#include "MavCommandQueue.h"
2
3#include <QtCore/QTimer>
4
5#include "FirmwarePlugin.h"
6#include "MAVLinkLib.h"
7#include "MAVLinkProtocol.h"
9#include "QGC.h"
10#include "QGCLoggingCategory.h"
11#include "Vehicle.h"
12#include "VehicleLinkManager.h"
13
14#ifdef QT_DEBUG
15#include "MockLink.h"
16#endif
17
18QGC_LOGGING_CATEGORY(MavCommandQueueLog, "Vehicle.MavCommandQueue")
19
21 : QObject(vehicle)
22 , _vehicle(vehicle)
23{
24 _responseCheckTimer.setSingleShot(false);
25 _responseCheckTimer.setInterval(_responseCheckIntervalMSecs());
26 _responseCheckTimer.start();
27 connect(&_responseCheckTimer, &QTimer::timeout, this, &MavCommandQueue::_responseTimeoutCheck);
28}
29
31{
32 _responseCheckTimer.stop();
33 _responseCheckTimer.disconnect();
34}
35
37{
38 qCDebug(MavCommandQueueLog) << "stop - clearing pending commands and halting response timer";
39 _stopped = true;
40 _responseCheckTimer.stop();
41 _responseCheckTimer.disconnect();
42 _list.clear();
43}
44
45void MavCommandQueue::sendCommand(int compId, MAV_CMD command, bool showError, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
46{
47 sendWorker(false, // commandInt
48 showError,
49 nullptr, // no handlers
50 compId,
51 command,
52 MAV_FRAME_GLOBAL,
53 param1, param2, param3, param4, param5, param6, param7);
54}
55
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)
57{
58 QTimer::singleShot(milliseconds, this, [=, this] {
59 sendCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
60 });
61}
62
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)
64{
65 sendWorker(true, // commandInt
66 showError,
67 nullptr, // no handlers
68 compId,
69 command,
70 frame,
71 param1, param2, param3, param4, param5, param6, param7);
72}
73
74void MavCommandQueue::sendCommandWithHandler(const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
75{
76 sendWorker(false, // commandInt
77 false, // showError
78 ackHandlerInfo,
79 compId,
80 command,
81 MAV_FRAME_GLOBAL,
82 param1, param2, param3, param4, param5, param6, param7);
83}
84
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)
86{
87 sendWorker(true, // commandInt
88 false, // showError
89 ackHandlerInfo,
90 compId,
91 command,
92 frame,
93 param1, param2, param3, param4, param5, param6, param7);
94}
95
96namespace {
97
98struct LambdaFallbackHandlerData {
99 Vehicle* vehicle;
100 bool showError;
101 std::function<void()> unsupportedLambda;
102};
103
104void lambdaFallbackResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, VehicleTypes::MavCmdResultFailureCode_t /*failureCode*/)
105{
106 auto* data = static_cast<LambdaFallbackHandlerData*>(resultHandlerData);
107 auto* instanceData = data->vehicle->firmwarePluginInstanceData();
108
109 switch (ack.result) {
110 case MAV_RESULT_ACCEPTED:
112 break;
113 case MAV_RESULT_UNSUPPORTED:
114 instanceData->setCommandSupported(MAV_CMD(ack.command), FirmwarePluginInstanceData::CommandSupportedResult::UNSUPPORTED);
115 data->unsupportedLambda();
116 break;
117 default:
118 if (data->showError) {
120 }
121 break;
122 }
123
124 delete data;
125}
126
127} // namespace
128
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)
130{
131 auto* instanceData = _vehicle->firmwarePluginInstanceData();
132
133 switch (instanceData->getCommandSupported(command)) {
135 lambda();
136 break;
138 sendCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
139 break;
141 auto* data = new LambdaFallbackHandlerData { _vehicle, showError, std::move(lambda) };
142 const MavCmdAckHandlerInfo_t handlerInfo {
143 /* .resultHandler = */ &lambdaFallbackResultHandler,
144 /* .resultHandlerData = */ data,
145 /* .progressHandler = */ nullptr,
146 /* .progressHandlerData = */ nullptr,
147 };
148 sendCommandWithHandler(&handlerInfo, compId, command, param1, param2, param3, param4, param5, param6, param7);
149 break;
150 }
151 }
152}
153
154bool MavCommandQueue::isPending(int targetCompId, MAV_CMD command) const
155{
156 return findEntryIndex(targetCompId, command) != -1;
157}
158
159int MavCommandQueue::findEntryIndex(int targetCompId, MAV_CMD command) const
160{
161 for (int i = 0; i < _list.count(); i++) {
162 const MavCommandListEntry_t& entry = _list[i];
163 if (entry.targetCompId == targetCompId && entry.command == command) {
164 return i;
165 }
166 }
167 return -1;
168}
169
170int MavCommandQueue::_responseCheckIntervalMSecs()
171{
172 // Use shorter check interval during unit tests for faster test execution
173 return QGC::runningUnitTests() ? 50 : 500;
174}
175
176int MavCommandQueue::_ackTimeoutMSecs()
177{
178 // Use shorter ack timeout during unit tests for faster test execution
180}
181
182bool MavCommandQueue::_shouldRetry(MAV_CMD command)
183{
184 switch (command) {
185#ifdef QT_DEBUG
186 // These MockLink commands should be retried so we can create unit tests to test retry code
192 return true;
193#endif
194
195 // In general we should not retry any commands. This is for safety reasons. For example you don't want an ARM command
196 // to timeout with no response over a noisy link twice and then suddenly have the third try work 6 seconds later. At that
197 // point the user could have walked up to the vehicle to see what is going wrong.
198 //
199 // We do retry commands which are part of the initial vehicle connect sequence. This makes this process work better over noisy
200 // links where commands could be lost. Also these commands tend to just be requesting status so if they end up being delayed
201 // there are no safety concerns that could occur.
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:
206 return true;
207
208 default:
209 return false;
210 }
211}
212
213bool MavCommandQueue::_canBeDuplicated(MAV_CMD command)
214{
215 // For some commands we don't care about response as much as we care about sending them regularly.
216 // This test avoids commands not being sent due to an ACK not being received yet.
217 // MOTOR_TEST in ardusub is a case where we need a constant stream of commands so it doesn't time out.
218 switch (command) {
219 case MAV_CMD_DO_MOTOR_TEST:
220 case MAV_CMD_SET_MESSAGE_INTERVAL:
221 return true;
222 default:
223 return false;
224 }
225}
226
227QString MavCommandQueue::_formatCommand(MAV_CMD command, float param1)
228{
229 QString rawName = MissionCommandTree::instance()->rawName(command);
230 QString friendlyName = MissionCommandTree::instance()->friendlyName(command);
231 QString commandStr = friendlyName.isEmpty() ? rawName : QStringLiteral("%1 (%2)").arg(friendlyName, rawName);
232
233 if (command == MAV_CMD_REQUEST_MESSAGE) {
234 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(static_cast<int>(param1));
235 if (info) {
236 commandStr += QStringLiteral(" [%1]").arg(info->name);
237 }
238 }
239
240 return commandStr;
241}
242
243void MavCommandQueue::sendWorker(bool commandInt, bool showError,
244 const MavCmdAckHandlerInfo_t* ackHandlerInfo,
245 int targetCompId, MAV_CMD command, MAV_FRAME frame,
246 float param1, float param2, float param3, float param4, double param5, double param6, float param7)
247{
248 if (_stopped) {
249 return;
250 }
251
252 // We can't send commands to compIdAll using this method. The reason being that we would get responses back possibly from multiple components
253 // which this code can't handle.
254 // We also can't send the majority of commands again if we are already waiting for a response from that same command. If we did that we would not be able to discern
255 // which ack was associated with which command.
256 if ((targetCompId == MAV_COMP_ID_ALL) || (isPending(targetCompId, command) && !_canBeDuplicated(command))) {
257 bool compIdAll = targetCompId == MAV_COMP_ID_ALL;
258 QString rawCommandName = MissionCommandTree::instance()->rawName(command);
259
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;
261
263 if (ackHandlerInfo && ackHandlerInfo->resultHandler) {
264 mavlink_command_ack_t ack = {};
265 ack.result = MAV_RESULT_FAILED;
266 (*ackHandlerInfo->resultHandler)(ackHandlerInfo->resultHandlerData, targetCompId, ack, failureCode);
267 } else {
268 emit commandResult(_vehicle->id(), targetCompId, command, MAV_RESULT_FAILED, failureCode);
269 }
270 if (showError) {
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.")));
272 }
273 return;
274 }
275
276 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
277 if (!sharedLink) {
278 qCDebug(MavCommandQueueLog) << "sendWorker: primary link gone!";
279
281 if (ackHandlerInfo && ackHandlerInfo->resultHandler) {
282 mavlink_command_ack_t ack = {};
283 ack.command = command;
284 ack.result = MAV_RESULT_FAILED;
285 (*ackHandlerInfo->resultHandler)(ackHandlerInfo->resultHandlerData, targetCompId, ack, failureCode);
286 } else {
287 emit commandResult(_vehicle->id(), targetCompId, command, MAV_RESULT_FAILED, failureCode);
288 }
289
290 if (showError) {
291 QGC::showAppMessage(tr("Unable to send command: Vehicle is not connected."));
292 }
293 return;
294 }
295
296 MavCommandListEntry_t entry;
297 entry.useCommandInt = commandInt;
298 entry.targetCompId = targetCompId;
299 entry.command = command;
300 entry.frame = frame;
301 entry.showError = showError;
302 entry.ackHandlerInfo = {};
303 if (ackHandlerInfo) {
304 entry.ackHandlerInfo = *ackHandlerInfo;
305 }
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;
313 entry.maxTries = _shouldRetry(command) ? kMaxRetryCount : 1;
314 entry.ackTimeoutMSecs = sharedLink->linkConfiguration()->isHighLatency() ? _ackTimeoutMSecsHighLatency : _ackTimeoutMSecs();
315 entry.elapsedTimer.start();
316
317 qCDebug(MavCommandQueueLog) << "Sending" << _formatCommand(command, param1) << "param1-7:" << command << param1 << param2 << param3 << param4 << param5 << param6 << param7;
318
319 _list.append(entry);
320 _sendFromList(_list.count() - 1);
321}
322
323void MavCommandQueue::_sendFromList(int index)
324{
325 MavCommandListEntry_t commandEntry = _list[index];
326
327 QString rawCommandName = MissionCommandTree::instance()->rawName(commandEntry.command);
328 QString friendlyName = MissionCommandTree::instance()->friendlyName(commandEntry.command);
329
330 if (++_list[index].tryCount > commandEntry.maxTries) {
331 QString logMsg = QStringLiteral("Giving up sending command after max retries: %1").arg(rawCommandName);
332
333 // For REQUEST_MESSAGE commands, also log which message was being requested
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));
338 }
339
340 qCWarning(MavCommandQueueLog) << logMsg;
341
342 _list.removeAt(index);
343 if (commandEntry.ackHandlerInfo.resultHandler) {
344 mavlink_command_ack_t ack = {};
345 ack.result = MAV_RESULT_FAILED;
346 (*commandEntry.ackHandlerInfo.resultHandler)(commandEntry.ackHandlerInfo.resultHandlerData, commandEntry.targetCompId, ack, MavCmdResultFailureNoResponseToCommand);
347 } else {
348 emit commandResult(_vehicle->id(), commandEntry.targetCompId, commandEntry.command, MAV_RESULT_FAILED, MavCmdResultFailureNoResponseToCommand);
349 }
350 if (commandEntry.showError) {
351 QGC::showAppMessage(tr("Vehicle did not respond to command: %1").arg(friendlyName));
352 }
353 return;
354 }
355
356 if (commandEntry.tryCount > 1 && !_vehicle->px4Firmware() && commandEntry.command == MAV_CMD_START_RX_PAIR) {
357 // The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares
358 // we aren't really sure whether they are correct or not.
359 return;
360 }
361
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;
364
365 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
366 if (!sharedLink) {
367 qCDebug(MavCommandQueueLog) << "_sendFromList: primary link gone!";
368 return;
369 }
370
372
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;
387 mavlink_msg_command_int_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
389 sharedLink->mavlinkChannel(),
390 &msg,
391 &cmd);
392 } else {
394 memset(&cmd, 0, sizeof(cmd));
395 cmd.target_system = _vehicle->id();
396 cmd.target_component = commandEntry.targetCompId;
397 cmd.command = commandEntry.command;
398 // MAVLink spec: confirmation increments on each resend.
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;
407 mavlink_msg_command_long_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
409 sharedLink->mavlinkChannel(),
410 &msg,
411 &cmd);
412 }
413
414 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
415}
416
417void MavCommandQueue::_responseTimeoutCheck()
418{
419 if (_list.isEmpty()) {
420 return;
421 }
422
423 // Walk the list backwards since _sendFromList can remove entries
424 for (int i = _list.count() - 1; i >= 0; i--) {
425 MavCommandListEntry_t& commandEntry = _list[i];
426 if (commandEntry.elapsedTimer.elapsed() > commandEntry.ackTimeoutMSecs) {
427 // Try sending command again
428 _sendFromList(i);
429 }
430 }
431}
432
434{
435 QString rawName = MissionCommandTree::instance()->rawName(static_cast<MAV_CMD>(ack.command));
436 QString friendlyName = MissionCommandTree::instance()->friendlyName(static_cast<MAV_CMD>(ack.command));
437 QString commandStr = friendlyName.isEmpty() ? rawName : QStringLiteral("%1 (%2)").arg(friendlyName, rawName);
438
439 switch (ack.result) {
440 case MAV_RESULT_TEMPORARILY_REJECTED:
441 QGC::showAppMessage(tr("%1 command temporarily rejected").arg(commandStr));
442 break;
443 case MAV_RESULT_DENIED:
444 QGC::showAppMessage(tr("%1 command denied").arg(commandStr));
445 break;
446 case MAV_RESULT_UNSUPPORTED:
447 QGC::showAppMessage(tr("%1 command not supported").arg(commandStr));
448 break;
449 case MAV_RESULT_FAILED:
450 QGC::showAppMessage(tr("%1 command failed").arg(commandStr));
451 break;
452 default:
453 // Do nothing
454 break;
455 }
456}
457
459{
460 int entryIndex = findEntryIndex(message.compid, static_cast<MAV_CMD>(ack.command));
461 if (entryIndex == -1) {
462 QString rawCommandName = MissionCommandTree::instance()->rawName(static_cast<MAV_CMD>(ack.command));
463 qCDebug(MavCommandQueueLog) << "handleCommandAck Ack not in list" << rawCommandName;
464 return;
465 }
466
467 if (ack.result == MAV_RESULT_IN_PROGRESS) {
468 MavCommandListEntry_t commandEntry;
469 if (_vehicle->px4Firmware() && ack.command == MAV_CMD_DO_AUTOTUNE_ENABLE) {
470 // Hack to support PX4 autotune which does not send final result ack and just sends in progress
471 commandEntry = _list.takeAt(entryIndex);
472 } else {
473 // Command has not completed yet, don't remove
474 MavCommandListEntry_t& commandEntryRef = _list[entryIndex];
475 commandEntryRef.maxTries = 1; // Vehicle responded to command so don't retry
476 commandEntryRef.elapsedTimer.start(); // We've heard from vehicle, restart elapsed timer for no ack received timeout
477 commandEntry = commandEntryRef;
478 }
479
480 if (commandEntry.ackHandlerInfo.progressHandler) {
481 (*commandEntry.ackHandlerInfo.progressHandler)(commandEntry.ackHandlerInfo.progressHandlerData, message.compid, ack);
482 }
483 return;
484 }
485
486 MavCommandListEntry_t commandEntry = _list.takeAt(entryIndex);
487 if (commandEntry.ackHandlerInfo.resultHandler) {
488 (*commandEntry.ackHandlerInfo.resultHandler)(commandEntry.ackHandlerInfo.resultHandlerData, message.compid, ack, MavCmdResultCommandResultOnly);
489 } else {
490 if (commandEntry.showError) {
492 }
493 emit commandResult(_vehicle->id(), message.compid, ack.command, ack.result, MavCmdResultCommandResultOnly);
494 }
495}
496
498{
499 switch (failureCode) {
501 return QStringLiteral("Command Result Only");
503 return QStringLiteral("No Response To Command");
505 return QStringLiteral("Duplicate Command");
506 default:
507 return QStringLiteral("Unknown (%1)").arg(failureCode);
508 }
509}
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.
WeakLinkInterfacePtr primaryLink() const
bool px4Firmware() const
Definition Vehicle.h:492
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:573
int id() const
Definition Vehicle.h:423
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1383
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:683
bool runningUnitTests()
True if the app is running in unit-test mode. Returns false if qgcApp() doesn't exist yet.
Definition QGC.cc:227
void showAppMessage(const QString &message, const QString &title)
Show a modal application message. Queued if the UI isn't ready yet.
Definition QGC.cc:206
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
@ 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.