QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PlanManager.cc
Go to the documentation of this file.
1#include "PlanManager.h"
2#include "Vehicle.h"
4#include "FirmwarePlugin.h"
5#include "MAVLinkProtocol.h"
7#include "AppMessages.h"
9
10QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManager.PlanManager")
11
12PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType)
13 : QObject (vehicle)
14 , _vehicle (vehicle)
15 , _planType (planType)
16 , _ackTimeoutTimer (nullptr)
17 , _expectedAck (AckNone)
18 , _transactionInProgress (TransactionNone)
19 , _resumeMission (false)
20 , _lastMissionRequest (-1)
21 , _missionItemCountToRead (-1)
22 , _currentMissionIndex (-1)
23 , _lastCurrentIndex (-1)
24{
25 _ackTimeoutTimer = new QTimer(this);
26 _ackTimeoutTimer->setSingleShot(true);
27
28 connect(_ackTimeoutTimer, &QTimer::timeout, this, &PlanManager::_ackTimeout);
29}
30
35
37{
39
40 emit progressPctChanged(0);
41
42 qCDebug(PlanManagerLog) << QStringLiteral("writeMissionItems %1 count:").arg(_planTypeString()) << _writeMissionItems.count();
43
44 // Prime write list
45 _itemIndicesToWrite.clear();
46 for (int i=0; i<_writeMissionItems.count(); i++) {
48 }
49
50 _retryCount = 0;
51 _setTransactionInProgress(TransactionWrite);
54}
55
56
57void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems)
58{
60 return;
61 }
62
63 if (inProgress()) {
64 qCDebug(PlanManagerLog) << QStringLiteral("writeMissionItems %1 called while transaction in progress").arg(_planTypeString());
65 return;
66 }
67
69
70 bool skipFirstItem = _planType == MAV_MISSION_TYPE_MISSION && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
71
72 if (skipFirstItem && missionItems.count() > 0) {
73 // First item is not going to be moved to _writeMissionItems, free it now.
74 delete missionItems[0];
75 }
76
77 int firstIndex = skipFirstItem ? 1 : 0;
78
79 for (int i=firstIndex; i<missionItems.count(); i++) {
80 MissionItem* item = missionItems[i];
81 _writeMissionItems.append(item); // PlanManager takes control of passed MissionItem
82
83 item->setIsCurrentItem(i == firstIndex);
84
85 if (skipFirstItem) {
86 // Home is in sequence 0, remainder of items start at sequence 1
87 item->setSequenceNumber(item->sequenceNumber() - 1);
88 if (item->command() == MAV_CMD_DO_JUMP) {
89 item->setParam1((int)item->param1() - 1);
90 }
91 }
92 }
93
95}
96
99{
100 qCDebug(PlanManagerLog) << QStringLiteral("_writeMissionCount %1 count:_retryCount").arg(_planTypeString()) << _writeMissionItems.count() << _retryCount;
101
103 if (sharedLink) {
104 mavlink_message_t message;
105
106 mavlink_msg_mission_count_pack_chan(
107 MAVLinkProtocol::instance()->getSystemId(),
109 sharedLink->mavlinkChannel(),
110 &message,
111 _vehicle->id(),
112 MAV_COMP_ID_AUTOPILOT1,
113 _writeMissionItems.count(),
114 _planType,
115 0
116 );
117
118 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
119 }
121}
122
124{
126 return;
127 }
128
129 qCDebug(PlanManagerLog) << QStringLiteral("loadFromVehicle %1 read sequence").arg(_planTypeString());
130
131 if (inProgress()) {
132 qCDebug(PlanManagerLog) << QStringLiteral("loadFromVehicle %1 called while transaction in progress").arg(_planTypeString());
133 return;
134 }
135
136 _retryCount = 0;
137 _setTransactionInProgress(TransactionRead);
139 _requestList();
140}
141
144{
145 qCDebug(PlanManagerLog) << QStringLiteral("_requestList %1 _planType:_retryCount").arg(_planTypeString()) << _planType << _retryCount;
146
147 _itemIndicesToRead.clear();
149
151 if (sharedLink){
152 mavlink_message_t message;
153 mavlink_msg_mission_request_list_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
155 sharedLink->mavlinkChannel(),
156 &message,
157 _vehicle->id(),
158 MAV_COMP_ID_AUTOPILOT1,
159 _planType);
160
161 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
162 }
164}
165
166void PlanManager::_ackTimeout(void)
167{
168 if (_expectedAck == AckNone) {
169 return;
170 }
171
172 switch (_expectedAck) {
173 case AckNone:
174 qCWarning(PlanManagerLog) << QStringLiteral("_ackTimeout %1 timeout with AckNone").arg(_planTypeString());
175 _sendError(InternalError, tr("Internal error occurred during Mission Item communication: _ackTimeOut:_expectedAck == AckNone"));
176 break;
177 case AckMissionCount:
178 // MISSION_COUNT message expected
180 _sendError(MaxRetryExceeded, tr("Mission request list failed, maximum retries exceeded."));
181 _finishTransaction(false);
182 } else {
183 _retryCount++;
184 qCDebug(PlanManagerLog) << tr("Retrying %1 REQUEST_LIST retry Count").arg(_planTypeString()) << _retryCount;
185 _requestList();
186 }
187 break;
188 case AckMissionItem:
189 // MISSION_ITEM expected
191 _sendError(MaxRetryExceeded, tr("Mission read failed, maximum retries exceeded."));
192 _finishTransaction(false);
193 } else {
194 _retryCount++;
195 qCDebug(PlanManagerLog) << tr("Retrying %1 MISSION_REQUEST retry Count").arg(_planTypeString()) << _retryCount;
197 }
198 break;
200 // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
201 if (_itemIndicesToWrite.count() == 0) {
202 // Vehicle did not send final MISSION_ACK at end of sequence
203 _sendError(ProtocolError, tr("Mission write failed, vehicle failed to send final ack."));
204 _finishTransaction(false);
205 } else if (_itemIndicesToWrite[0] == 0) {
206 // Vehicle did not respond to MISSION_COUNT, try again
208 _sendError(MaxRetryExceeded, tr("Mission write mission count failed, maximum retries exceeded."));
209 _finishTransaction(false);
210 } else {
211 _retryCount++;
212 qCDebug(PlanManagerLog) << QStringLiteral("Retrying %1 MISSION_COUNT retry Count").arg(_planTypeString()) << _retryCount;
214 }
215 } else {
216 // Vehicle did not request all items from ground station
217 _sendError(ProtocolError, tr("Vehicle did not request all items from ground station: %1").arg(_ackTypeToString(_expectedAck)));
219 _finishTransaction(false);
220 }
221 break;
223 // MISSION_ACK expected
225 _sendError(MaxRetryExceeded, tr("Mission remove all, maximum retries exceeded."));
226 _finishTransaction(false);
227 } else {
228 _retryCount++;
229 qCDebug(PlanManagerLog) << tr("Retrying %1 MISSION_CLEAR_ALL retry Count").arg(_planTypeString()) << _retryCount;
231 }
232 break;
233 case AckGuidedItem:
234 // MISSION_REQUEST is expected, or MISSION_ACK to end sequence
235 default:
236 _sendError(AckTimeoutError, tr("Vehicle did not respond to mission item communication: %1").arg(_ackTypeToString(_expectedAck)));
238 _finishTransaction(false);
239 }
240}
241
243{
244 // Use much shorter timeouts in unit tests since MockLink responds instantly
245 const int retryTimeout = QGC::runningUnitTests() ? 10 : _retryTimeoutMilliseconds;
247
248 switch (ack) {
249 case AckMissionItem:
250 // We are actively trying to get the mission item, so we don't want to wait as long.
251 _ackTimeoutTimer->setInterval(retryTimeout);
252 break;
253 case AckNone:
254 // FALLTHROUGH
255 case AckMissionCount:
256 // FALLTHROUGH
258 // FALLTHROUGH
260 // FALLTHROUGH
261 case AckGuidedItem:
262 _ackTimeoutTimer->setInterval(ackTimeout);
263 break;
264 }
265
266 _expectedAck = ack;
267 _ackTimeoutTimer->start();
268}
269
273{
274 if (receivedAck == _expectedAck) {
276 _ackTimeoutTimer->stop();
277 return true;
278 } else {
279 if (_expectedAck == AckNone) {
280 // Don't worry about unexpected mission commands, just ignore them; ArduPilot updates home position using
281 // spurious MISSION_ITEMs.
282 } else {
283 // We just warn in this case, this could be crap left over from a previous transaction or the vehicle going bonkers.
284 // Whatever it is we let the ack timeout handle any error output to the user.
285 qCDebug(PlanManagerLog) << QString("Out of sequence ack %1 expected:received %2:%3").arg(_planTypeString()).arg(_ackTypeToString(_expectedAck)).arg(_ackTypeToString(receivedAck));
286 }
287 return false;
288 }
289}
290
292{
293 qCDebug(PlanManagerLog) << "_readTransactionComplete read sequence complete";
294
296 if (sharedLink) {
297 mavlink_message_t message;
298
299 mavlink_msg_mission_ack_pack_chan(
300 MAVLinkProtocol::instance()->getSystemId(),
302 sharedLink->mavlinkChannel(),
303 &message,
304 _vehicle->id(),
305 MAV_COMP_ID_AUTOPILOT1,
306 MAV_MISSION_ACCEPTED,
307 _planType,
308 0
309 );
310
311 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
312 }
313
314 _finishTransaction(true);
315}
316
318{
319 mavlink_mission_count_t missionCount;
320
321 mavlink_msg_mission_count_decode(&message, &missionCount);
322
323 if (missionCount.mission_type != _planType) {
324 // if there was a previous transaction with a different mission_type, it can happen that we receive
325 // a stale message here, for example when the MAV ran into a timeout and sent a message twice
326 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionCount %1 Incorrect mission_type received expected:actual").arg(_planTypeString()) << _planType << missionCount.mission_type;
327 return;
328 }
329
331 return;
332 }
333
334 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionCount %1 count:").arg(_planTypeString()) << missionCount.count;
335
336 _retryCount = 0;
337
338 if (missionCount.count == 0) {
340 } else {
341 // Prime read list
342 for (int i=0; i<missionCount.count; i++) {
344 }
345 _missionItemCountToRead = missionCount.count;
347 }
348}
349
351{
352 if (_itemIndicesToRead.count() == 0) {
353 _sendError(InternalError, tr("Internal Error: Call to Vehicle _requestNextMissionItem with no more indices to read"));
354 return;
355 }
356
357 qCDebug(PlanManagerLog) << QStringLiteral("_requestNextMissionItem %1 sequenceNumber:retry").arg(_planTypeString()) << _itemIndicesToRead[0] << _retryCount;
358
360 if (sharedLink) {
361 mavlink_message_t message;
362
363 mavlink_msg_mission_request_int_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
365 sharedLink->mavlinkChannel(),
366 &message,
367 _vehicle->id(),
368 MAV_COMP_ID_AUTOPILOT1,
370 _planType);
371 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
372 }
374}
375
377{
378 MAV_CMD command;
379 MAV_FRAME frame;
380 MAV_MISSION_TYPE missionType;
381 double param1;
382 double param2;
383 double param3;
384 double param4;
385 double param5;
386 double param6;
387 double param7;
388 bool autoContinue;
389 bool isCurrentItem;
390 int seq;
391
392 mavlink_mission_item_int_t missionItem;
393 mavlink_msg_mission_item_int_decode(&message, &missionItem);
394
395 command = (MAV_CMD)missionItem.command;
396 frame = (MAV_FRAME)missionItem.frame;
397 missionType = (MAV_MISSION_TYPE)missionItem.mission_type;
398 param1 = missionItem.param1;
399 param2 = missionItem.param2;
400 param3 = missionItem.param3;
401 param4 = missionItem.param4;
402 param5 = missionItem.frame == MAV_FRAME_MISSION ? (double)missionItem.x : (double)missionItem.x * 1e-7;
403 param6 = missionItem.frame == MAV_FRAME_MISSION ? (double)missionItem.y : (double)missionItem.y * 1e-7;
404 param7 = (double)missionItem.z;
405 autoContinue = missionItem.autocontinue;
406 isCurrentItem = missionItem.current;
407 seq = missionItem.seq;
408
409 // Check the mission_type field. It can happen that we receive a late duplicate message for a
410 // different mission_type request.
411 if (missionType != _planType) {
412 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionItem %1 dropping spurious item seq:command:missionType").arg(_planTypeString()) << seq << command << missionType;
413 return;
414 }
415
416 // We don't support editing ALT_INT frames so change on the way in.
417 if (frame == MAV_FRAME_GLOBAL_INT) {
418 frame = MAV_FRAME_GLOBAL;
419 } else if (frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
420 frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
421 }
422
423 bool ardupilotHomePositionUpdate = false;
425 if (_vehicle->apmFirmware() && seq == 0 && _planType == MAV_MISSION_TYPE_MISSION) {
426 ardupilotHomePositionUpdate = true;
427 } else {
428 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionItem %1 dropping spurious item seq:command:current").arg(_planTypeString()) << seq << command << isCurrentItem;
429 return;
430 }
431 }
432
433 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionItem %1 seq:command:current:ardupilotHomePositionUpdate").arg(_planTypeString()) << seq << command << isCurrentItem << ardupilotHomePositionUpdate;
434
435 if (ardupilotHomePositionUpdate) {
436 QGeoCoordinate newHomePosition(param5, param6, param7);
437 _vehicle->_setHomePosition(newHomePosition);
438 return;
439 }
440
441 if (_itemIndicesToRead.contains(seq)) {
442 _itemIndicesToRead.removeOne(seq);
443
444 MissionItem* item = new MissionItem(seq,
445 command,
446 frame,
447 param1,
448 param2,
449 param3,
450 param4,
451 param5,
452 param6,
453 param7,
454 autoContinue,
455 isCurrentItem,
456 this);
457
458 if (item->command() == MAV_CMD_DO_JUMP && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
459 // Home is in position 0
460 item->setParam1((int)item->param1() + 1);
461 }
462
463 _missionItems.append(item);
464 } else {
465 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionItem %1 mission item received item index which was not requested, disregrarding:").arg(_planTypeString()) << seq;
466 // We have to put the ack timeout back since it was removed above
468 return;
469 }
470
471 emit progressPctChanged((double)seq / (double)_missionItemCountToRead);
472
473 _retryCount = 0;
474 if (_itemIndicesToRead.count() == 0) {
476 } else {
478 }
479}
480
486
488{
489 MAV_MISSION_TYPE missionRequestMissionType;
490 uint16_t missionRequestSeq;
491
492 mavlink_mission_request_int_t missionRequest;
493 mavlink_msg_mission_request_int_decode(&message, &missionRequest);
494 missionRequestMissionType = static_cast<MAV_MISSION_TYPE>(missionRequest.mission_type);
495 missionRequestSeq = missionRequest.seq;
496
497 if (missionRequestMissionType != _planType) {
498 // if there was a previous transaction with a different mission_type, it can happen that we receive
499 // a stale message here, for example when the MAV ran into a timeout and sent a message twice
500 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 Incorrect mission_type received expected:actual").arg(_planTypeString()) << _planType << missionRequestMissionType;
501 return;
502 }
503
505 return;
506 }
507
508 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 sequenceNumber").arg(_planTypeString()) << missionRequestSeq;
509
510 if (missionRequestSeq > _writeMissionItems.count() - 1) {
511 _sendError(RequestRangeError, tr("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_writeMissionItems.count()).arg(missionRequestSeq));
512 _finishTransaction(false);
513 return;
514 }
515
516 emit progressPctChanged((double)missionRequestSeq / (double)_writeMissionItems.count());
517
518 _lastMissionRequest = missionRequestSeq;
519 if (!_itemIndicesToWrite.contains(missionRequestSeq)) {
520 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 sequence number requested which has already been sent, sending again:").arg(_planTypeString()) << missionRequestSeq;
521 } else {
522 _itemIndicesToWrite.removeOne(missionRequestSeq);
523 }
524
525 MissionItem* item = _writeMissionItems[missionRequestSeq];
526 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 sequenceNumber:command").arg(_planTypeString()) << missionRequestSeq << item->command();
527
529 if (sharedLink) {
530 mavlink_message_t messageOut;
531
532 mavlink_msg_mission_item_int_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
534 sharedLink->mavlinkChannel(),
535 &messageOut,
536 _vehicle->id(),
537 MAV_COMP_ID_AUTOPILOT1,
538 missionRequestSeq,
539 item->frame(),
540 item->command(),
541 missionRequestSeq == 0,
542 item->autoContinue(),
543 item->param1(),
544 item->param2(),
545 item->param3(),
546 item->param4(),
547 item->frame() == MAV_FRAME_MISSION ? item->param5() : item->param5() * 1e7,
548 item->frame() == MAV_FRAME_MISSION ? item->param6() : item->param6() * 1e7,
549 item->param7(),
550 _planType);
551 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), messageOut);
552 }
554}
555
557{
558 mavlink_mission_ack_t missionAck;
559
560 mavlink_msg_mission_ack_decode(&message, &missionAck);
561 if (missionAck.mission_type != _planType) {
562 // if there was a previous transaction with a different mission_type, it can happen that we receive
563 // a stale message here, for example when the MAV ran into a timeout and sent a message twice
564 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck %1 Incorrect mission_type received expected:actual").arg(_planTypeString()) << _planType << missionAck.mission_type;
565 return;
566 }
567
568 if (_vehicle->apmFirmware() && missionAck.type == MAV_MISSION_INVALID_SEQUENCE) {
569 // ArduPilot sends these Acks which can happen just due to noisy links causing duplicated requests being responded to.
570 // As far as I'm concerned this is incorrect protocol implementation but we need to deal with it anyway. So we just
571 // ignore it and if things really go haywire the timeouts will fire to fail the overall transaction.
572 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE").arg(_planTypeString()) << _planType;
573 return;
574 }
575
576 // Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
577 // type of a protocol sequence we are in.
578 AckType_t savedExpectedAck = _expectedAck;
579
580 // We can get a MISSION_ACK with an error at any time, so if the Acks don't match it is not
581 // a protocol sequence error. Call _checkForExpectedAck with _retryAck so it will succeed no
582 // matter what.
584 return;
585 }
586
587 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck %1 type:").arg(_planTypeString()) << _missionResultToString((MAV_MISSION_RESULT)missionAck.type);
588
589 switch (savedExpectedAck) {
590 case AckNone:
591 // State machine is idle. Vehicle is confused.
592 qCDebug(PlanManagerLog) << QStringLiteral("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type));
593 break;
594 case AckMissionCount:
595 // MISSION_COUNT message expected
596 // FIXME: Protocol error
597 _sendError(VehicleAckError, _missionResultToString((MAV_MISSION_RESULT)missionAck.type));
598 _finishTransaction(false);
599 break;
600 case AckMissionItem:
601 // MISSION_ITEM expected
602 // FIXME: Protocol error
603 _sendError(VehicleAckError, _missionResultToString((MAV_MISSION_RESULT)missionAck.type));
604 _finishTransaction(false);
605 break;
607 // MISSION_REQUEST is expected, or MAV_MISSION_ACCEPTED to end sequence
608 if (missionAck.type == MAV_MISSION_ACCEPTED) {
609 if (_itemIndicesToWrite.count() == 0) {
610 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck write sequence complete %1").arg(_planTypeString());
611 _finishTransaction(true);
612 } else {
613 // FIXME: Protocol error
614 _sendError(VehicleAckError, _missionResultToString((MAV_MISSION_RESULT)missionAck.type));
615 _finishTransaction(false);
616 }
617 } else {
618 _sendError(VehicleAckError, _missionResultToString((MAV_MISSION_RESULT)missionAck.type));
619 _finishTransaction(false);
620 }
621 break;
623 // MAV_MISSION_ACCEPTED expected
624 if (missionAck.type != MAV_MISSION_ACCEPTED) {
625 _sendError(VehicleAckError, tr("Vehicle remove all failed. Error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
626 }
627 _finishTransaction(missionAck.type == MAV_MISSION_ACCEPTED);
628 break;
629 case AckGuidedItem:
630 // MISSION_REQUEST is expected, or MAV_MISSION_ACCEPTED to end sequence
631 if (missionAck.type == MAV_MISSION_ACCEPTED) {
632 qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionAck %1 guided mode item accepted").arg(_planTypeString());
633 _finishTransaction(true, true /* apmGuidedItemWrite */);
634 } else {
635 // FIXME: Protocol error
636 _sendError(VehicleAckError, tr("Vehicle returned error: %1. %2Vehicle did not accept guided item.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
637 _finishTransaction(false, true /* apmGuidedItemWrite */);
638 }
639 break;
640 }
641}
642
644void PlanManager::_mavlinkMessageReceived(const mavlink_message_t& message)
645{
646 switch (message.msgid) {
647 case MAVLINK_MSG_ID_MISSION_COUNT:
648 _handleMissionCount(message);
649 break;
650
651 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
652 _handleMissionItem(message);
653 break;
654
655 case MAVLINK_MSG_ID_MISSION_REQUEST:
656 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
657 _handleMissionRequest(message);
658 break;
659
660 case MAVLINK_MSG_ID_MISSION_ACK:
661 _handleMissionAck(message);
662 break;
663 }
664}
665
666void PlanManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
667{
668 qCDebug(PlanManagerLog) << QStringLiteral("Sending error - _planTypeString(%1) errorCode(%2) errorMsg(%4)").arg(_planTypeString()).arg(errorCode).arg(errorMsg);
669
670 emit error(errorCode, errorMsg);
671}
672
674{
675 switch (ackType) {
676 case AckNone:
677 return QString("No Ack");
678 case AckMissionCount:
679 return QString("MISSION_COUNT");
680 case AckMissionItem:
681 return QString("MISSION_ITEM");
683 return QString("MISSION_REQUEST");
684 case AckGuidedItem:
685 return QString("Guided Mode Item");
686 default:
687 qWarning(PlanManagerLog) << QStringLiteral("Fell off end of switch statement %1").arg(_planTypeString());
688 return QString("QGC Internal Error");
689 }
690}
691
692QString PlanManager::_lastMissionReqestString(MAV_MISSION_RESULT result)
693{
694 QString prefix;
695 QString postfix;
696
699
700 prefix = tr("Item #%1 Command: %2").arg(_lastMissionRequest).arg(MissionCommandTree::instance()->friendlyName(item->command()));
701
702 switch (result) {
703 case MAV_MISSION_UNSUPPORTED_FRAME:
704 postfix = tr("Frame: %1").arg(item->frame());
705 break;
706 case MAV_MISSION_UNSUPPORTED:
707 // All we need is the prefix
708 break;
709 case MAV_MISSION_INVALID_PARAM1:
710 postfix = tr("Value: %1").arg(item->param1());
711 break;
712 case MAV_MISSION_INVALID_PARAM2:
713 postfix = tr("Value: %1").arg(item->param2());
714 break;
715 case MAV_MISSION_INVALID_PARAM3:
716 postfix = tr("Value: %1").arg(item->param3());
717 break;
718 case MAV_MISSION_INVALID_PARAM4:
719 postfix = tr("Value: %1").arg(item->param4());
720 break;
721 case MAV_MISSION_INVALID_PARAM5_X:
722 postfix = tr("Value: %1").arg(item->param5());
723 break;
724 case MAV_MISSION_INVALID_PARAM6_Y:
725 postfix = tr("Value: %1").arg(item->param6());
726 break;
727 case MAV_MISSION_INVALID_PARAM7:
728 postfix = tr("Value: %1").arg(item->param7());
729 break;
730 case MAV_MISSION_INVALID_SEQUENCE:
731 // All we need is the prefix
732 break;
733 default:
734 break;
735 }
736 }
737
738 return prefix + (postfix.isEmpty() ? QStringLiteral("") : QStringLiteral(" ")) + postfix;
739}
740
741QString PlanManager::_missionResultToString(MAV_MISSION_RESULT result)
742{
743 QString error;
744
745 switch (result) {
746 case MAV_MISSION_ACCEPTED:
747 error = tr("Mission accepted.");
748 break;
749 case MAV_MISSION_ERROR:
750 error = tr("Unspecified error.");
751 break;
752 case MAV_MISSION_UNSUPPORTED_FRAME:
753 error = tr("Coordinate frame is not supported.");
754 break;
755 case MAV_MISSION_UNSUPPORTED:
756 error = tr("Command is not supported.");
757 break;
758 case MAV_MISSION_NO_SPACE:
759 error = tr("Mission item exceeds storage space.");
760 break;
761 case MAV_MISSION_INVALID:
762 error = tr("One of the parameters has an invalid value.");
763 break;
764 case MAV_MISSION_INVALID_PARAM1:
765 error = tr("Param 1 invalid value.");
766 break;
767 case MAV_MISSION_INVALID_PARAM2:
768 error = tr("Param 2 invalid value.");
769 break;
770 case MAV_MISSION_INVALID_PARAM3:
771 error = tr("Param 3 invalid value.");
772 break;
773 case MAV_MISSION_INVALID_PARAM4:
774 error = tr("Param 4 invalid value.");
775 break;
776 case MAV_MISSION_INVALID_PARAM5_X:
777 error = tr("Param 5 invalid value.");
778 break;
779 case MAV_MISSION_INVALID_PARAM6_Y:
780 error = tr("Param 6 invalid value.");
781 break;
782 case MAV_MISSION_INVALID_PARAM7:
783 error = tr("Param 7 invalid value.");
784 break;
785 case MAV_MISSION_INVALID_SEQUENCE:
786 error = tr("Received mission item out of sequence.");
787 break;
788 case MAV_MISSION_DENIED:
789 error = tr("Not accepting any mission commands.");
790 break;
791 default:
792 qWarning(PlanManagerLog) << QStringLiteral("Fell off end of switch statement %1 %2").arg(_planTypeString()).arg(result);
793 error = tr("Unknown error: %1.").arg(result);
794 break;
795 }
796
797 QString lastRequestString = _lastMissionReqestString(result);
798 if (!lastRequestString.isEmpty()) {
799 error += QStringLiteral(" ") + lastRequestString;
800 }
801
802 return error;
803}
804
805void PlanManager::_finishTransaction(bool success, bool apmGuidedItemWrite)
806{
807 emit progressPctChanged(1);
809
810 _itemIndicesToRead.clear();
811 _itemIndicesToWrite.clear();
812
813 // First thing we do is clear the transaction. This way inProgesss is off when we signal transaction complete.
814 TransactionType_t currentTransactionType = _transactionInProgress;
815 _setTransactionInProgress(TransactionNone);
816
817 switch (currentTransactionType) {
818 case TransactionRead:
819 if (!success) {
820 // Read from vehicle failed, clear partial list
822 }
823 emit newMissionItemsAvailable(false);
824 break;
825 case TransactionWrite:
826 // No need to do anything for ArduPilot guided go to waypoint write
827 if (!apmGuidedItemWrite) {
828 if (success) {
829 // Write succeeded, update internal list to be current
830 if (_planType == MAV_MISSION_TYPE_MISSION) {
833 emit currentIndexChanged(-1);
835 }
837 for (int i=0; i<_writeMissionItems.count(); i++) {
839 }
840 _writeMissionItems.clear();
841 } else {
842 // Write failed, throw out the write list
844 }
845 emit sendComplete(!success /* error */);
846 }
847 break;
849 emit removeAllComplete(!success /* error */);
850 break;
851 default:
852 break;
853 }
854
855 if (_resumeMission) {
856 _resumeMission = false;
857 if (success) {
858 emit resumeMissionReady();
859 } else {
861 }
862 }
863}
864
866{
868}
869
871{
872 qCDebug(PlanManagerLog) << "_removeAllWorker";
873
874 emit progressPctChanged(0);
875
877
879 if (sharedLink) {
880 mavlink_message_t message;
881
882 mavlink_msg_mission_clear_all_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
884 sharedLink->mavlinkChannel(),
885 &message,
886 _vehicle->id(),
887 MAV_COMP_ID_AUTOPILOT1,
888 _planType);
889 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
890 }
892}
893
895{
896 if (inProgress()) {
897 return;
898 }
899
900 qCDebug(PlanManagerLog) << QStringLiteral("removeAll %1").arg(_planTypeString());
901
903
904 if (_planType == MAV_MISSION_TYPE_MISSION) {
907 emit currentIndexChanged(-1);
909 }
910
911 _retryCount = 0;
912 _setTransactionInProgress(TransactionRemoveAll);
913
915}
916
918{
919 for (int i=0; i<_missionItems.count(); i++) {
920 // Using deleteLater here causes too much transient memory to stack up
921 delete _missionItems[i];
922 }
923 _missionItems.clear();
924}
925
926
928{
929 for (int i=0; i<_writeMissionItems.count(); i++) {
930 // Using deleteLater here causes too much transient memory to stack up
931 delete _writeMissionItems[i];
932 }
933 _writeMissionItems.clear();
934}
935
937{
938 connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived);
939}
940
942{
943 disconnect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived);
944}
945
947{
948 switch (_planType) {
949 case MAV_MISSION_TYPE_MISSION:
950 return QStringLiteral("T:Mission");
951 case MAV_MISSION_TYPE_FENCE:
952 return QStringLiteral("T:GeoFence");
953 case MAV_MISSION_TYPE_RALLY:
954 return QStringLiteral("T:Rally");
955 default:
956 qWarning() << "Unknown plan type" << _planType;
957 return QStringLiteral("T:Unknown");
958 }
959}
960
961void PlanManager::_setTransactionInProgress(TransactionType_t type)
962{
963 if (_transactionInProgress != type) {
964 qCDebug(PlanManagerLog) << "_setTransactionInProgress" << _planTypeString() << type;
967 }
968}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Error error
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
virtual bool sendHomePositionToVehicle() const
static int getComponentId()
static MAVLinkProtocol * instance()
static MissionCommandTree * instance()
MAV_CMD command(void) const
Definition MissionItem.h:49
double param5(void) const
Definition MissionItem.h:58
double param7(void) const
Definition MissionItem.h:60
void setParam1(double param1)
MAV_FRAME frame(void) const
Definition MissionItem.h:52
void setIsCurrentItem(bool isCurrentItem)
bool autoContinue(void) const
Definition MissionItem.h:53
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
int sequenceNumber(void) const
Definition MissionItem.h:51
double param4(void) const
Definition MissionItem.h:57
void setSequenceNumber(int sequenceNumber)
double param2(void) const
Definition MissionItem.h:55
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
Definition PlanManager.h:14
int _currentMissionIndex
bool _resumeMission
QList< MissionItem * > _missionItems
Set of mission items on vehicle.
void resumeMissionUploadFail(void)
QList< int > _itemIndicesToRead
List of mission items which still need to be requested from vehicle.
int _lastMissionRequest
Index of item last requested by MISSION_REQUEST.
TransactionType_t _transactionInProgress
bool _checkForExpectedAck(AckType_t receivedAck)
void _handleMissionRequest(const mavlink_message_t &message)
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void _handleMissionItem(const mavlink_message_t &message)
void resumeMissionReady(void)
void removeAll(void)
void _clearAndDeleteWriteMissionItems(void)
QTimer * _ackTimeoutTimer
ErrorCode_t
Error codes returned in error signal.
Definition PlanManager.h:45
@ AckTimeoutError
Timed out waiting for response from vehicle.
Definition PlanManager.h:47
@ MaxRetryExceeded
Retry failed.
Definition PlanManager.h:53
@ ProtocolError
Incorrect protocol sequence from vehicle.
Definition PlanManager.h:48
@ RequestRangeError
Vehicle requested item out of range.
Definition PlanManager.h:49
@ VehicleAckError
Vehicle returned error in ack.
Definition PlanManager.h:51
int _missionItemCountToRead
Count of all mission items to read.
static constexpr int kTestAckTimeoutMs
Ack timeout used in unit tests (much shorter for faster tests)
Definition PlanManager.h:65
int _lastCurrentIndex
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
QString _missionResultToString(MAV_MISSION_RESULT result)
QString _lastMissionReqestString(MAV_MISSION_RESULT result)
static constexpr int _maxRetryCount
Definition PlanManager.h:62
void _finishTransaction(bool success, bool apmGuidedItemWrite=false)
void _requestList(void)
Internal call to request list of mission items. May be called during a retry sequence.
void _writeMissionItemsWorker(void)
void _connectToMavlink(void)
AckType_t _expectedAck
static constexpr int _ackTimeoutMilliseconds
Definition PlanManager.h:59
void _startAckTimeout(AckType_t ack)
void loadFromVehicle(void)
void _sendError(ErrorCode_t errorCode, const QString &errorMsg)
void removeAllComplete(bool error)
void writeMissionItems(const QList< MissionItem * > &missionItems)
QList< int > _itemIndicesToWrite
List of mission items which still need to be written to vehicle.
void _handleMissionAck(const mavlink_message_t &message)
void _removeAllWorker(void)
@ TransactionRemoveAll
Definition PlanManager.h:97
void _clearMissionItems(void)
bool inProgress(void) const
void inProgressChanged(bool inProgress)
QList< MissionItem * > _writeMissionItems
Set of mission items currently being written to vehicle.
void progressPctChanged(double progressPercentPct)
void _clearAndDeleteMissionItems(void)
@ AckMissionItem
MISSION_ITEM expected.
Definition PlanManager.h:87
@ AckMissionRequest
MISSION_REQUEST is expected, or MISSION_ACK to end sequence.
Definition PlanManager.h:88
@ AckMissionCount
MISSION_COUNT message expected.
Definition PlanManager.h:86
@ AckMissionClearAll
MISSION_CLEAR_ALL sent, MISSION_ACK is expected.
Definition PlanManager.h:89
@ AckNone
State machine is idle.
Definition PlanManager.h:85
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
Definition PlanManager.h:90
QString _planTypeString(void)
static constexpr int _retryTimeoutMilliseconds
Definition PlanManager.h:61
const QList< MissionItem * > & missionItems(void)
Definition PlanManager.h:22
void _requestNextMissionItem(void)
void _writeMissionCount(void)
This begins the write sequence with the vehicle. This may be called during a retry.
QString _ackTypeToString(AckType_t ackType)
void _handleMissionCount(const mavlink_message_t &message)
void _disconnectFromMavlink(void)
Vehicle * _vehicle
void _readTransactionComplete(void)
WeakLinkInterfacePtr primaryLink() const
void _setHomePosition(QGeoCoordinate &homeCoord)
Definition Vehicle.cc:1188
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
bool isOfflineEditingVehicle() const
Definition Vehicle.h:510
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
void mavlinkMessageReceived(const mavlink_message_t &message)
bool apmFirmware() const
Definition Vehicle.h:495
bool runningUnitTests()