15 , _cachedLastCurrentIndex (-1)
28 qCDebug(MissionManagerLog) <<
"writeArduPilotGuidedMissionItem called while transaction in progress";
39 mavlink_mission_item_t missionItem;
41 memset(&missionItem, 0,
sizeof(missionItem));
45 missionItem.command = MAV_CMD_NAV_WAYPOINT;
46 missionItem.param1 = 0;
47 missionItem.param2 = 0;
48 missionItem.param3 = 0;
49 missionItem.param4 = 0;
50 missionItem.x = gotoCoord.latitude();
51 missionItem.y = gotoCoord.longitude();
52 missionItem.z = gotoCoord.altitude();
53 missionItem.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
54 missionItem.current = altChangeOnly ? 3 : 2;
55 missionItem.autocontinue =
true;
59 sharedLink->mavlinkChannel(),
76 qCDebug(MissionManagerLog) <<
"generateResumeMission called while transaction in progress";
82 if (item->
command() == MAV_CMD_DO_JUMP) {
83 QGC::showAppMessage(tr(
"Unable to generate resume mission due to MAV_CMD_DO_JUMP command."));
89 resumeIndex = qMax(0, qMin(resumeIndex,
_missionItems.count() - 1));
95 while (--resumeIndex > 0) {
104 resumeIndex = qMax(0, resumeIndex);
106 QList<MissionItem*> resumeMission;
108 QList<MAV_CMD> includedResumeCommands;
111 includedResumeCommands << MAV_CMD_DO_CONTROL_VIDEO
112 << MAV_CMD_DO_SET_ROI
113 << MAV_CMD_DO_DIGICAM_CONFIGURE
114 << MAV_CMD_DO_DIGICAM_CONTROL
115 << MAV_CMD_DO_MOUNT_CONFIGURE
116 << MAV_CMD_DO_MOUNT_CONTROL
117 << MAV_CMD_DO_SET_CAM_TRIGG_DIST
118 << MAV_CMD_DO_FENCE_ENABLE
119 << MAV_CMD_IMAGE_START_CAPTURE
120 << MAV_CMD_IMAGE_STOP_CAPTURE
121 << MAV_CMD_VIDEO_START_CAPTURE
122 << MAV_CMD_VIDEO_STOP_CAPTURE
123 << MAV_CMD_DO_CHANGE_SPEED
124 << MAV_CMD_SET_CAMERA_MODE;
128 int prefixCommandCount = 0;
132 if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->
command()) || (loopUiInfo && loopUiInfo->
isTakeoffCommand())) {
133 if (i < resumeIndex) {
134 prefixCommandCount++;
138 resumeMission.append(newItem);
141 prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count()));
144 bool foundROI =
false;
145 bool foundCameraSetMode =
false;
146 bool foundCameraStartStop =
false;
147 prefixCommandCount--;
148 while (prefixCommandCount >= 0) {
149 MissionItem* resumeItem = resumeMission[prefixCommandCount];
150 switch (resumeItem->
command()) {
151 case MAV_CMD_SET_CAMERA_MODE:
153 if (foundCameraSetMode) {
154 resumeMission.removeAt(prefixCommandCount);
156 foundCameraSetMode =
true;
158 case MAV_CMD_DO_SET_ROI:
161 resumeMission.removeAt(prefixCommandCount);
165 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
166 case MAV_CMD_IMAGE_STOP_CAPTURE:
167 case MAV_CMD_VIDEO_START_CAPTURE:
168 case MAV_CMD_VIDEO_STOP_CAPTURE:
170 if (foundCameraStartStop) {
171 resumeMission.removeAt(prefixCommandCount);
173 foundCameraStartStop =
true;
175 case MAV_CMD_IMAGE_START_CAPTURE:
176 if (resumeItem->
param3() != 0) {
178 resumeMission.removeAt(prefixCommandCount);
181 if (foundCameraStartStop) {
183 resumeMission.removeAt(prefixCommandCount);
185 foundCameraStartStop =
true;
191 prefixCommandCount--;
196 for (
int i=0; i<resumeMission.count(); i++) {
199 int setCurrentIndex = addHomePosition ? 1 : 0;
200 resumeMission[setCurrentIndex]->setIsCurrentItem(
true);
204 for (
int i=0; i<resumeMission.count(); i++) {
214 switch (message.msgid) {
215 case MAVLINK_MSG_ID_HIGH_LATENCY:
216 _handleHighLatency(message);
219 case MAVLINK_MSG_ID_HIGH_LATENCY2:
220 _handleHighLatency2(message);
223 case MAVLINK_MSG_ID_MISSION_CURRENT:
224 _handleMissionCurrent(message);
227 case MAVLINK_MSG_ID_HEARTBEAT:
228 _handleHeartbeat(message);
233void MissionManager::_updateMissionIndex(
int index)
236 qCDebug(MissionManagerLog) <<
"_updateMissionIndex currentIndex:" << index;
248 qCDebug(MissionManagerLog) <<
"_updateMissionIndex caching _lastCurrentIndex for possible update:" <<
_currentMissionIndex;
255 mavlink_high_latency_t highLatency;
256 mavlink_msg_high_latency_decode(&message, &highLatency);
257 _updateMissionIndex(highLatency.wp_num);
263 mavlink_msg_high_latency2_decode(&message, &highLatency2);
264 _updateMissionIndex(highLatency2.wp_num);
269 mavlink_mission_current_t missionCurrent;
270 mavlink_msg_mission_current_decode(&message, &missionCurrent);
271 _updateMissionIndex(missionCurrent.seq);
279 qCDebug(MissionManagerLog) <<
"_handleHeartbeat updating lastCurrentIndex from cached value:" << _cachedLastCurrentIndex;
281 _cachedLastCurrentIndex = -1;
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_high_latency2_t mavlink_high_latency2_t
virtual bool sendHomePositionToVehicle() const
static int getComponentId()
static MAVLinkProtocol * instance()
static MissionCommandTree * instance()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
UI Information associated with a mission command (MAV_CMD)
bool isTakeoffCommand(void) const
bool specifiesCoordinate(void) const
bool isStandaloneCoordinate(void) const
MAV_CMD command(void) const
void setIsCurrentItem(bool isCurrentItem)
double param3(void) const
void setSequenceNumber(int sequenceNumber)
void generateResumeMission(int resumeIndex)
void writeArduPilotGuidedMissionItem(const QGeoCoordinate &gotoCoord, bool altChangeOnly)
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
QList< MissionItem * > _missionItems
Set of mission items on vehicle.
TransactionType_t _transactionInProgress
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void _clearAndDeleteWriteMissionItems(void)
void _writeMissionItemsWorker(void)
void _connectToMavlink(void)
void _startAckTimeout(AckType_t ack)
bool inProgress(void) const
void inProgressChanged(bool inProgress)
QList< MissionItem * > _writeMissionItems
Set of mission items currently being written to vehicle.
@ AckGuidedItem
MISSION_ACK expected in response to ArduPilot guided mode single item send.
WeakLinkInterfacePtr primaryLink() const
QGCMAVLink::VehicleClass_t vehicleClass(void) const
QString missionFlightMode() const
QString flightMode() const
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)
int defaultComponentId() const
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.