14 , _cachedLastCurrentIndex (-1)
27 qCDebug(MissionManagerLog) <<
"writeArduPilotGuidedMissionItem called while transaction in progress";
38 mavlink_mission_item_t missionItem;
40 memset(&missionItem, 0,
sizeof(missionItem));
44 missionItem.command = MAV_CMD_NAV_WAYPOINT;
45 missionItem.param1 = 0;
46 missionItem.param2 = 0;
47 missionItem.param3 = 0;
48 missionItem.param4 = 0;
49 missionItem.x = gotoCoord.latitude();
50 missionItem.y = gotoCoord.longitude();
51 missionItem.z = gotoCoord.altitude();
52 missionItem.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
53 missionItem.current = altChangeOnly ? 3 : 2;
54 missionItem.autocontinue =
true;
58 sharedLink->mavlinkChannel(),
75 qCDebug(MissionManagerLog) <<
"generateResumeMission called while transaction in progress";
81 if (item->
command() == MAV_CMD_DO_JUMP) {
82 qgcApp()->showAppMessage(tr(
"Unable to generate resume mission due to MAV_CMD_DO_JUMP command."));
88 resumeIndex = qMax(0, qMin(resumeIndex,
_missionItems.count() - 1));
94 while (--resumeIndex > 0) {
103 resumeIndex = qMax(0, resumeIndex);
105 QList<MissionItem*> resumeMission;
107 QList<MAV_CMD> includedResumeCommands;
110 includedResumeCommands << MAV_CMD_DO_CONTROL_VIDEO
111 << MAV_CMD_DO_SET_ROI
112 << MAV_CMD_DO_DIGICAM_CONFIGURE
113 << MAV_CMD_DO_DIGICAM_CONTROL
114 << MAV_CMD_DO_MOUNT_CONFIGURE
115 << MAV_CMD_DO_MOUNT_CONTROL
116 << MAV_CMD_DO_SET_CAM_TRIGG_DIST
117 << MAV_CMD_DO_FENCE_ENABLE
118 << MAV_CMD_IMAGE_START_CAPTURE
119 << MAV_CMD_IMAGE_STOP_CAPTURE
120 << MAV_CMD_VIDEO_START_CAPTURE
121 << MAV_CMD_VIDEO_STOP_CAPTURE
122 << MAV_CMD_DO_CHANGE_SPEED
123 << MAV_CMD_SET_CAMERA_MODE;
127 int prefixCommandCount = 0;
131 if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->
command()) || (loopUiInfo && loopUiInfo->
isTakeoffCommand())) {
132 if (i < resumeIndex) {
133 prefixCommandCount++;
137 resumeMission.append(newItem);
140 prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count()));
143 bool foundROI =
false;
144 bool foundCameraSetMode =
false;
145 bool foundCameraStartStop =
false;
146 prefixCommandCount--;
147 while (prefixCommandCount >= 0) {
148 MissionItem* resumeItem = resumeMission[prefixCommandCount];
149 switch (resumeItem->
command()) {
150 case MAV_CMD_SET_CAMERA_MODE:
152 if (foundCameraSetMode) {
153 resumeMission.removeAt(prefixCommandCount);
155 foundCameraSetMode =
true;
157 case MAV_CMD_DO_SET_ROI:
160 resumeMission.removeAt(prefixCommandCount);
164 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
165 case MAV_CMD_IMAGE_STOP_CAPTURE:
166 case MAV_CMD_VIDEO_START_CAPTURE:
167 case MAV_CMD_VIDEO_STOP_CAPTURE:
169 if (foundCameraStartStop) {
170 resumeMission.removeAt(prefixCommandCount);
172 foundCameraStartStop =
true;
174 case MAV_CMD_IMAGE_START_CAPTURE:
175 if (resumeItem->
param3() != 0) {
177 resumeMission.removeAt(prefixCommandCount);
180 if (foundCameraStartStop) {
182 resumeMission.removeAt(prefixCommandCount);
184 foundCameraStartStop =
true;
190 prefixCommandCount--;
195 for (
int i=0; i<resumeMission.count(); i++) {
198 int setCurrentIndex = addHomePosition ? 1 : 0;
199 resumeMission[setCurrentIndex]->setIsCurrentItem(
true);
203 for (
int i=0; i<resumeMission.count(); i++) {
213 switch (message.msgid) {
214 case MAVLINK_MSG_ID_HIGH_LATENCY:
215 _handleHighLatency(message);
218 case MAVLINK_MSG_ID_HIGH_LATENCY2:
219 _handleHighLatency2(message);
222 case MAVLINK_MSG_ID_MISSION_CURRENT:
223 _handleMissionCurrent(message);
226 case MAVLINK_MSG_ID_HEARTBEAT:
227 _handleHeartbeat(message);
232void MissionManager::_updateMissionIndex(
int index)
235 qCDebug(MissionManagerLog) <<
"_updateMissionIndex currentIndex:" << index;
247 qCDebug(MissionManagerLog) <<
"_updateMissionIndex caching _lastCurrentIndex for possible update:" <<
_currentMissionIndex;
254 mavlink_high_latency_t highLatency;
255 mavlink_msg_high_latency_decode(&message, &highLatency);
256 _updateMissionIndex(highLatency.wp_num);
261 mavlink_high_latency2_t highLatency2;
262 mavlink_msg_high_latency2_decode(&message, &highLatency2);
263 _updateMissionIndex(highLatency2.wp_num);
268 mavlink_mission_current_t missionCurrent;
269 mavlink_msg_mission_current_decode(&message, &missionCurrent);
270 _updateMissionIndex(missionCurrent.seq);
278 qCDebug(MissionManagerLog) <<
"_handleHeartbeat updating lastCurrentIndex from cached value:" << _cachedLastCurrentIndex;
280 _cachedLastCurrentIndex = -1;
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()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
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)
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