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)
24 _ackTimeoutTimer =
new QTimer(
this);
25 _ackTimeoutTimer->setSingleShot(
true);
27 connect(_ackTimeoutTimer, &QTimer::timeout,
this, &PlanManager::_ackTimeout);
63 qCDebug(PlanManagerLog) << QStringLiteral(
"writeMissionItems %1 called while transaction in progress").arg(
_planTypeString());
76 int firstIndex = skipFirstItem ? 1 : 0;
87 if (item->
command() == MAV_CMD_DO_JUMP) {
105 mavlink_msg_mission_count_pack_chan(
108 sharedLink->mavlinkChannel(),
111 MAV_COMP_ID_AUTOPILOT1,
128 qCDebug(PlanManagerLog) << QStringLiteral(
"loadFromVehicle %1 read sequence").arg(
_planTypeString());
131 qCDebug(PlanManagerLog) << QStringLiteral(
"loadFromVehicle %1 called while transaction in progress").arg(
_planTypeString());
154 sharedLink->mavlinkChannel(),
157 MAV_COMP_ID_AUTOPILOT1,
165void PlanManager::_ackTimeout(
void)
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"));
292 qCDebug(PlanManagerLog) <<
"_readTransactionComplete read sequence complete";
298 mavlink_msg_mission_ack_pack_chan(
301 sharedLink->mavlinkChannel(),
304 MAV_COMP_ID_AUTOPILOT1,
305 MAV_MISSION_ACCEPTED,
318 mavlink_mission_count_t missionCount;
320 mavlink_msg_mission_count_decode(&message, &missionCount);
322 if (missionCount.mission_type !=
_planType) {
325 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionCount %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionCount.mission_type;
333 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionCount %1 count:").arg(
_planTypeString()) << missionCount.count;
337 if (missionCount.count == 0) {
341 for (
int i=0; i<missionCount.count; i++) {
352 _sendError(
InternalError, tr(
"Internal Error: Call to Vehicle _requestNextMissionItem with no more indices to read"));
364 sharedLink->mavlinkChannel(),
367 MAV_COMP_ID_AUTOPILOT1,
379 MAV_MISSION_TYPE missionType;
391 mavlink_mission_item_int_t missionItem;
392 mavlink_msg_mission_item_int_decode(&message, &missionItem);
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;
411 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 dropping spurious item seq:command:missionType").arg(
_planTypeString()) << seq << command << missionType;
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;
422 bool ardupilotHomePositionUpdate =
false;
425 ardupilotHomePositionUpdate =
true;
427 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 dropping spurious item seq:command:current").arg(
_planTypeString()) << seq << command << isCurrentItem;
432 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 seq:command:current:ardupilotHomePositionUpdate").arg(
_planTypeString()) << seq << command << isCurrentItem << ardupilotHomePositionUpdate;
434 if (ardupilotHomePositionUpdate) {
435 QGeoCoordinate newHomePosition(param5, param6, param7);
464 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 mission item received item index which was not requested, disregrarding:").arg(
_planTypeString()) << seq;
488 MAV_MISSION_TYPE missionRequestMissionType;
489 uint16_t missionRequestSeq;
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;
496 if (missionRequestMissionType !=
_planType) {
499 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionRequestMissionType;
507 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequenceNumber").arg(
_planTypeString()) << missionRequestSeq;
519 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequence number requested which has already been sent, sending again:").arg(
_planTypeString()) << missionRequestSeq;
525 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequenceNumber:command").arg(
_planTypeString()) << missionRequestSeq << item->
command();
533 sharedLink->mavlinkChannel(),
536 MAV_COMP_ID_AUTOPILOT1,
540 missionRequestSeq == 0,
557 mavlink_mission_ack_t missionAck;
559 mavlink_msg_mission_ack_decode(&message, &missionAck);
560 if (missionAck.mission_type !=
_planType) {
563 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionAck.mission_type;
571 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE").arg(
_planTypeString()) <<
_planType;
588 switch (savedExpectedAck) {
591 qCDebug(PlanManagerLog) << QStringLiteral(
"Vehicle sent unexpected MISSION_ACK message, error: %1").arg(
_missionResultToString((MAV_MISSION_RESULT)missionAck.type));
607 if (missionAck.type == MAV_MISSION_ACCEPTED) {
609 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck write sequence complete %1").arg(
_planTypeString());
623 if (missionAck.type != MAV_MISSION_ACCEPTED) {
630 if (missionAck.type == MAV_MISSION_ACCEPTED) {
631 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck %1 guided mode item accepted").arg(
_planTypeString());
645 switch (message.msgid) {
646 case MAVLINK_MSG_ID_MISSION_COUNT:
650 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
654 case MAVLINK_MSG_ID_MISSION_REQUEST:
655 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
659 case MAVLINK_MSG_ID_MISSION_ACK:
667 qCDebug(PlanManagerLog) << QStringLiteral(
"Sending error - _planTypeString(%1) errorCode(%2) errorMsg(%4)").arg(
_planTypeString()).arg(errorCode).arg(errorMsg);
669 emit
error(errorCode, errorMsg);
676 return QString(
"No Ack");
678 return QString(
"MISSION_COUNT");
680 return QString(
"MISSION_ITEM");
682 return QString(
"MISSION_REQUEST");
684 return QString(
"Guided Mode Item");
686 qWarning(PlanManagerLog) << QStringLiteral(
"Fell off end of switch statement %1").arg(
_planTypeString());
687 return QString(
"QGC Internal Error");
702 case MAV_MISSION_UNSUPPORTED_FRAME:
703 postfix = tr(
"Frame: %1").arg(item->
frame());
705 case MAV_MISSION_UNSUPPORTED:
708 case MAV_MISSION_INVALID_PARAM1:
709 postfix = tr(
"Value: %1").arg(item->
param1());
711 case MAV_MISSION_INVALID_PARAM2:
712 postfix = tr(
"Value: %1").arg(item->
param2());
714 case MAV_MISSION_INVALID_PARAM3:
715 postfix = tr(
"Value: %1").arg(item->
param3());
717 case MAV_MISSION_INVALID_PARAM4:
718 postfix = tr(
"Value: %1").arg(item->
param4());
720 case MAV_MISSION_INVALID_PARAM5_X:
721 postfix = tr(
"Value: %1").arg(item->
param5());
723 case MAV_MISSION_INVALID_PARAM6_Y:
724 postfix = tr(
"Value: %1").arg(item->
param6());
726 case MAV_MISSION_INVALID_PARAM7:
727 postfix = tr(
"Value: %1").arg(item->
param7());
729 case MAV_MISSION_INVALID_SEQUENCE:
737 return prefix + (postfix.isEmpty() ? QStringLiteral(
"") : QStringLiteral(
" ")) + postfix;
745 case MAV_MISSION_ACCEPTED:
746 error = tr(
"Mission accepted.");
748 case MAV_MISSION_ERROR:
749 error = tr(
"Unspecified error.");
751 case MAV_MISSION_UNSUPPORTED_FRAME:
752 error = tr(
"Coordinate frame is not supported.");
754 case MAV_MISSION_UNSUPPORTED:
755 error = tr(
"Command is not supported.");
757 case MAV_MISSION_NO_SPACE:
758 error = tr(
"Mission item exceeds storage space.");
760 case MAV_MISSION_INVALID:
761 error = tr(
"One of the parameters has an invalid value.");
763 case MAV_MISSION_INVALID_PARAM1:
764 error = tr(
"Param 1 invalid value.");
766 case MAV_MISSION_INVALID_PARAM2:
767 error = tr(
"Param 2 invalid value.");
769 case MAV_MISSION_INVALID_PARAM3:
770 error = tr(
"Param 3 invalid value.");
772 case MAV_MISSION_INVALID_PARAM4:
773 error = tr(
"Param 4 invalid value.");
775 case MAV_MISSION_INVALID_PARAM5_X:
776 error = tr(
"Param 5 invalid value.");
778 case MAV_MISSION_INVALID_PARAM6_Y:
779 error = tr(
"Param 6 invalid value.");
781 case MAV_MISSION_INVALID_PARAM7:
782 error = tr(
"Param 7 invalid value.");
784 case MAV_MISSION_INVALID_SEQUENCE:
785 error = tr(
"Received mission item out of sequence.");
787 case MAV_MISSION_DENIED:
788 error = tr(
"Not accepting any mission commands.");
791 qWarning(PlanManagerLog) << QStringLiteral(
"Fell off end of switch statement %1 %2").arg(
_planTypeString()).arg(result);
792 error = tr(
"Unknown error: %1.").arg(result);
797 if (!lastRequestString.isEmpty()) {
798 error += QStringLiteral(
" ") + lastRequestString;
816 switch (currentTransactionType) {
826 if (!apmGuidedItemWrite) {
829 if (
_planType == MAV_MISSION_TYPE_MISSION) {
871 qCDebug(PlanManagerLog) <<
"_removeAllWorker";
883 sharedLink->mavlinkChannel(),
886 MAV_COMP_ID_AUTOPILOT1,
899 qCDebug(PlanManagerLog) << QStringLiteral(
"removeAll %1").arg(
_planTypeString());
903 if (
_planType == MAV_MISSION_TYPE_MISSION) {
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");
955 qWarning() <<
"Unknown plan type" <<
_planType;
956 return QStringLiteral(
"T:Unknown");
960void PlanManager::_setTransactionInProgress(TransactionType_t type)
963 qCDebug(PlanManagerLog) <<
"_setTransactionInProgress" <<
_planTypeString() << type;
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
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
double param5(void) const
double param7(void) const
void setParam1(double param1)
MAV_FRAME frame(void) const
void setIsCurrentItem(bool isCurrentItem)
bool autoContinue(void) const
double param3(void) const
double param6(void) const
double param1(void) const
int sequenceNumber(void) const
double param4(void) const
void setSequenceNumber(int sequenceNumber)
double param2(void) const
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 _clearAndDeleteWriteMissionItems(void)
QTimer * _ackTimeoutTimer
ErrorCode_t
Error codes returned in error signal.
@ AckTimeoutError
Timed out waiting for response from vehicle.
@ MaxRetryExceeded
Retry failed.
@ ProtocolError
Incorrect protocol sequence from vehicle.
@ RequestRangeError
Vehicle requested item out of range.
@ VehicleAckError
Vehicle returned error in ack.
int _missionItemCountToRead
Count of all mission items to read.
static constexpr int kTestAckTimeoutMs
Ack timeout used in unit tests (much shorter for faster tests)
void newMissionItemsAvailable(bool removeAllRequested)
MAV_MISSION_TYPE _planType
QString _missionResultToString(MAV_MISSION_RESULT result)
QString _lastMissionReqestString(MAV_MISSION_RESULT result)
static constexpr int _maxRetryCount
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)
static constexpr int _ackTimeoutMilliseconds
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.
@ AckMissionRequest
MISSION_REQUEST is expected, or MISSION_ACK to end sequence.
@ AckMissionCount
MISSION_COUNT message expected.
@ AckMissionClearAll
MISSION_CLEAR_ALL sent, MISSION_ACK is expected.
@ AckNone
State machine is idle.
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
QString _planTypeString(void)
static constexpr int _retryTimeoutMilliseconds
const QList< MissionItem * > & missionItems(void)
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)
void _readTransactionComplete(void)
WeakLinkInterfacePtr primaryLink() const
void _setHomePosition(QGeoCoordinate &homeCoord)
VehicleLinkManager * vehicleLinkManager()
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
bool isOfflineEditingVehicle() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
void mavlinkMessageReceived(const mavlink_message_t &message)