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)
25 _ackTimeoutTimer =
new QTimer(
this);
26 _ackTimeoutTimer->setSingleShot(
true);
28 connect(_ackTimeoutTimer, &QTimer::timeout,
this, &PlanManager::_ackTimeout);
64 qCDebug(PlanManagerLog) << QStringLiteral(
"writeMissionItems %1 called while transaction in progress").arg(
_planTypeString());
77 int firstIndex = skipFirstItem ? 1 : 0;
88 if (item->
command() == MAV_CMD_DO_JUMP) {
106 mavlink_msg_mission_count_pack_chan(
109 sharedLink->mavlinkChannel(),
112 MAV_COMP_ID_AUTOPILOT1,
129 qCDebug(PlanManagerLog) << QStringLiteral(
"loadFromVehicle %1 read sequence").arg(
_planTypeString());
132 qCDebug(PlanManagerLog) << QStringLiteral(
"loadFromVehicle %1 called while transaction in progress").arg(
_planTypeString());
155 sharedLink->mavlinkChannel(),
158 MAV_COMP_ID_AUTOPILOT1,
166void PlanManager::_ackTimeout(
void)
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"));
293 qCDebug(PlanManagerLog) <<
"_readTransactionComplete read sequence complete";
299 mavlink_msg_mission_ack_pack_chan(
302 sharedLink->mavlinkChannel(),
305 MAV_COMP_ID_AUTOPILOT1,
306 MAV_MISSION_ACCEPTED,
319 mavlink_mission_count_t missionCount;
321 mavlink_msg_mission_count_decode(&message, &missionCount);
323 if (missionCount.mission_type !=
_planType) {
326 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionCount %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionCount.mission_type;
334 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionCount %1 count:").arg(
_planTypeString()) << missionCount.count;
338 if (missionCount.count == 0) {
342 for (
int i=0; i<missionCount.count; i++) {
353 _sendError(
InternalError, tr(
"Internal Error: Call to Vehicle _requestNextMissionItem with no more indices to read"));
365 sharedLink->mavlinkChannel(),
368 MAV_COMP_ID_AUTOPILOT1,
380 MAV_MISSION_TYPE missionType;
392 mavlink_mission_item_int_t missionItem;
393 mavlink_msg_mission_item_int_decode(&message, &missionItem);
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;
412 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 dropping spurious item seq:command:missionType").arg(
_planTypeString()) << seq << command << missionType;
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;
423 bool ardupilotHomePositionUpdate =
false;
426 ardupilotHomePositionUpdate =
true;
428 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 dropping spurious item seq:command:current").arg(
_planTypeString()) << seq << command << isCurrentItem;
433 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 seq:command:current:ardupilotHomePositionUpdate").arg(
_planTypeString()) << seq << command << isCurrentItem << ardupilotHomePositionUpdate;
435 if (ardupilotHomePositionUpdate) {
436 QGeoCoordinate newHomePosition(param5, param6, param7);
465 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionItem %1 mission item received item index which was not requested, disregrarding:").arg(
_planTypeString()) << seq;
489 MAV_MISSION_TYPE missionRequestMissionType;
490 uint16_t missionRequestSeq;
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;
497 if (missionRequestMissionType !=
_planType) {
500 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionRequestMissionType;
508 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequenceNumber").arg(
_planTypeString()) << missionRequestSeq;
520 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequence number requested which has already been sent, sending again:").arg(
_planTypeString()) << missionRequestSeq;
526 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionRequest %1 sequenceNumber:command").arg(
_planTypeString()) << missionRequestSeq << item->
command();
534 sharedLink->mavlinkChannel(),
537 MAV_COMP_ID_AUTOPILOT1,
541 missionRequestSeq == 0,
558 mavlink_mission_ack_t missionAck;
560 mavlink_msg_mission_ack_decode(&message, &missionAck);
561 if (missionAck.mission_type !=
_planType) {
564 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck %1 Incorrect mission_type received expected:actual").arg(
_planTypeString()) <<
_planType << missionAck.mission_type;
572 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE").arg(
_planTypeString()) <<
_planType;
589 switch (savedExpectedAck) {
592 qCDebug(PlanManagerLog) << QStringLiteral(
"Vehicle sent unexpected MISSION_ACK message, error: %1").arg(
_missionResultToString((MAV_MISSION_RESULT)missionAck.type));
608 if (missionAck.type == MAV_MISSION_ACCEPTED) {
610 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck write sequence complete %1").arg(
_planTypeString());
624 if (missionAck.type != MAV_MISSION_ACCEPTED) {
631 if (missionAck.type == MAV_MISSION_ACCEPTED) {
632 qCDebug(PlanManagerLog) << QStringLiteral(
"_handleMissionAck %1 guided mode item accepted").arg(
_planTypeString());
646 switch (message.msgid) {
647 case MAVLINK_MSG_ID_MISSION_COUNT:
651 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
655 case MAVLINK_MSG_ID_MISSION_REQUEST:
656 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
660 case MAVLINK_MSG_ID_MISSION_ACK:
668 qCDebug(PlanManagerLog) << QStringLiteral(
"Sending error - _planTypeString(%1) errorCode(%2) errorMsg(%4)").arg(
_planTypeString()).arg(errorCode).arg(errorMsg);
670 emit
error(errorCode, errorMsg);
677 return QString(
"No Ack");
679 return QString(
"MISSION_COUNT");
681 return QString(
"MISSION_ITEM");
683 return QString(
"MISSION_REQUEST");
685 return QString(
"Guided Mode Item");
687 qWarning(PlanManagerLog) << QStringLiteral(
"Fell off end of switch statement %1").arg(
_planTypeString());
688 return QString(
"QGC Internal Error");
703 case MAV_MISSION_UNSUPPORTED_FRAME:
704 postfix = tr(
"Frame: %1").arg(item->
frame());
706 case MAV_MISSION_UNSUPPORTED:
709 case MAV_MISSION_INVALID_PARAM1:
710 postfix = tr(
"Value: %1").arg(item->
param1());
712 case MAV_MISSION_INVALID_PARAM2:
713 postfix = tr(
"Value: %1").arg(item->
param2());
715 case MAV_MISSION_INVALID_PARAM3:
716 postfix = tr(
"Value: %1").arg(item->
param3());
718 case MAV_MISSION_INVALID_PARAM4:
719 postfix = tr(
"Value: %1").arg(item->
param4());
721 case MAV_MISSION_INVALID_PARAM5_X:
722 postfix = tr(
"Value: %1").arg(item->
param5());
724 case MAV_MISSION_INVALID_PARAM6_Y:
725 postfix = tr(
"Value: %1").arg(item->
param6());
727 case MAV_MISSION_INVALID_PARAM7:
728 postfix = tr(
"Value: %1").arg(item->
param7());
730 case MAV_MISSION_INVALID_SEQUENCE:
738 return prefix + (postfix.isEmpty() ? QStringLiteral(
"") : QStringLiteral(
" ")) + postfix;
746 case MAV_MISSION_ACCEPTED:
747 error = tr(
"Mission accepted.");
749 case MAV_MISSION_ERROR:
750 error = tr(
"Unspecified error.");
752 case MAV_MISSION_UNSUPPORTED_FRAME:
753 error = tr(
"Coordinate frame is not supported.");
755 case MAV_MISSION_UNSUPPORTED:
756 error = tr(
"Command is not supported.");
758 case MAV_MISSION_NO_SPACE:
759 error = tr(
"Mission item exceeds storage space.");
761 case MAV_MISSION_INVALID:
762 error = tr(
"One of the parameters has an invalid value.");
764 case MAV_MISSION_INVALID_PARAM1:
765 error = tr(
"Param 1 invalid value.");
767 case MAV_MISSION_INVALID_PARAM2:
768 error = tr(
"Param 2 invalid value.");
770 case MAV_MISSION_INVALID_PARAM3:
771 error = tr(
"Param 3 invalid value.");
773 case MAV_MISSION_INVALID_PARAM4:
774 error = tr(
"Param 4 invalid value.");
776 case MAV_MISSION_INVALID_PARAM5_X:
777 error = tr(
"Param 5 invalid value.");
779 case MAV_MISSION_INVALID_PARAM6_Y:
780 error = tr(
"Param 6 invalid value.");
782 case MAV_MISSION_INVALID_PARAM7:
783 error = tr(
"Param 7 invalid value.");
785 case MAV_MISSION_INVALID_SEQUENCE:
786 error = tr(
"Received mission item out of sequence.");
788 case MAV_MISSION_DENIED:
789 error = tr(
"Not accepting any mission commands.");
792 qWarning(PlanManagerLog) << QStringLiteral(
"Fell off end of switch statement %1 %2").arg(
_planTypeString()).arg(result);
793 error = tr(
"Unknown error: %1.").arg(result);
798 if (!lastRequestString.isEmpty()) {
799 error += QStringLiteral(
" ") + lastRequestString;
817 switch (currentTransactionType) {
827 if (!apmGuidedItemWrite) {
830 if (
_planType == MAV_MISSION_TYPE_MISSION) {
872 qCDebug(PlanManagerLog) <<
"_removeAllWorker";
884 sharedLink->mavlinkChannel(),
887 MAV_COMP_ID_AUTOPILOT1,
900 qCDebug(PlanManagerLog) << QStringLiteral(
"removeAll %1").arg(
_planTypeString());
904 if (
_planType == MAV_MISSION_TYPE_MISSION) {
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");
956 qWarning() <<
"Unknown plan type" <<
_planType;
957 return QStringLiteral(
"T:Unknown");
961void PlanManager::_setTransactionInProgress(TransactionType_t type)
964 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()
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
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
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)