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