QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionManager.cc
Go to the documentation of this file.
1#include "MissionManager.h"
2#include "Vehicle.h"
3#include "FirmwarePlugin.h"
4#include "MAVLinkProtocol.h"
5#include "QGCApplication.h"
9
10QGC_LOGGING_CATEGORY(MissionManagerLog, "PlanManager.MissionManager")
11
13 : PlanManager (vehicle, MAV_MISSION_TYPE_MISSION)
14 , _cachedLastCurrentIndex (-1)
15{
16 connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &MissionManager::_mavlinkMessageReceived);
17}
18
23
24void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly)
25{
26 if (inProgress()) {
27 qCDebug(MissionManagerLog) << "writeArduPilotGuidedMissionItem called while transaction in progress";
28 return;
29 }
30
32
34
36 if (sharedLink) {
37 mavlink_message_t messageOut;
38 mavlink_mission_item_t missionItem;
39
40 memset(&missionItem, 0, sizeof(missionItem));
41 missionItem.target_system = _vehicle->id();
42 missionItem.target_component = _vehicle->defaultComponentId();
43 missionItem.seq = 0;
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;
55
56 mavlink_msg_mission_item_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
58 sharedLink->mavlinkChannel(),
59 &messageOut,
60 &missionItem);
61
62 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), messageOut);
63 }
65 emit inProgressChanged(true);
66}
67
69{
71 return;
72 }
73
74 if (inProgress()) {
75 qCDebug(MissionManagerLog) << "generateResumeMission called while transaction in progress";
76 return;
77 }
78
79 for (int i=0; i<_missionItems.count(); i++) {
80 MissionItem* item = _missionItems[i];
81 if (item->command() == MAV_CMD_DO_JUMP) {
82 qgcApp()->showAppMessage(tr("Unable to generate resume mission due to MAV_CMD_DO_JUMP command."));
83 return;
84 }
85 }
86
87 // Be anal about crap input
88 resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1));
89
90 // Adjust resume index to be a location based command
92 if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) {
93 // We have to back up to the last command which the vehicle flies through
94 while (--resumeIndex > 0) {
95 uiInfo = MissionCommandTree::instance()->getUIInfo(_vehicle, _vehicle->vehicleClass(), _missionItems[resumeIndex]->command());
96 if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) {
97 // Found it
98 break;
99 }
100
101 }
102 }
103 resumeIndex = qMax(0, resumeIndex);
104
105 QList<MissionItem*> resumeMission;
106
107 QList<MAV_CMD> includedResumeCommands;
108
109 // If any command in this list occurs before the resumeIndex it will be added to the front of the mission
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;
124
125 bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle();
126
127 int prefixCommandCount = 0;
128 for (int i=0; i<_missionItems.count(); i++) {
129 MissionItem* oldItem = _missionItems[i];
131 if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command()) || (loopUiInfo && loopUiInfo->isTakeoffCommand())) {
132 if (i < resumeIndex) {
133 prefixCommandCount++;
134 }
135 MissionItem* newItem = new MissionItem(*oldItem, this);
136 newItem->setIsCurrentItem(false);
137 resumeMission.append(newItem);
138 }
139 }
140 prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count())); // Anal prevention against crashes
141
142 // De-dup and remove no-ops from the commands which were added to the front of the mission
143 bool foundROI = false;
144 bool foundCameraSetMode = false;
145 bool foundCameraStartStop = false;
146 prefixCommandCount--; // Change from count to array index
147 while (prefixCommandCount >= 0) {
148 MissionItem* resumeItem = resumeMission[prefixCommandCount];
149 switch (resumeItem->command()) {
150 case MAV_CMD_SET_CAMERA_MODE:
151 // Only keep the last one
152 if (foundCameraSetMode) {
153 resumeMission.removeAt(prefixCommandCount);
154 }
155 foundCameraSetMode = true;
156 break;
157 case MAV_CMD_DO_SET_ROI:
158 // Only keep the last one
159 if (foundROI) {
160 resumeMission.removeAt(prefixCommandCount);
161 }
162 foundROI = true;
163 break;
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:
168 // Only keep the first of these commands that are found
169 if (foundCameraStartStop) {
170 resumeMission.removeAt(prefixCommandCount);
171 }
172 foundCameraStartStop = true;
173 break;
174 case MAV_CMD_IMAGE_START_CAPTURE:
175 if (resumeItem->param3() != 0) {
176 // Remove commands which do not trigger by time
177 resumeMission.removeAt(prefixCommandCount);
178 break;
179 }
180 if (foundCameraStartStop) {
181 // Only keep the first of these commands that are found
182 resumeMission.removeAt(prefixCommandCount);
183 }
184 foundCameraStartStop = true;
185 break;
186 default:
187 break;
188 }
189
190 prefixCommandCount--;
191 }
192
193 // Adjust sequence numbers and current item
194 int seqNum = 0;
195 for (int i=0; i<resumeMission.count(); i++) {
196 resumeMission[i]->setSequenceNumber(seqNum++);
197 }
198 int setCurrentIndex = addHomePosition ? 1 : 0;
199 resumeMission[setCurrentIndex]->setIsCurrentItem(true);
200
201 // Send to vehicle
203 for (int i=0; i<resumeMission.count(); i++) {
204 _writeMissionItems.append(new MissionItem(*resumeMission[i], this));
205 }
206 _resumeMission = true;
208}
209
211void MissionManager::_mavlinkMessageReceived(const mavlink_message_t& message)
212{
213 switch (message.msgid) {
214 case MAVLINK_MSG_ID_HIGH_LATENCY:
215 _handleHighLatency(message);
216 break;
217
218 case MAVLINK_MSG_ID_HIGH_LATENCY2:
219 _handleHighLatency2(message);
220 break;
221
222 case MAVLINK_MSG_ID_MISSION_CURRENT:
223 _handleMissionCurrent(message);
224 break;
225
226 case MAVLINK_MSG_ID_HEARTBEAT:
227 _handleHeartbeat(message);
228 break;
229 }
230}
231
232void MissionManager::_updateMissionIndex(int index)
233{
234 if (index != _currentMissionIndex) {
235 qCDebug(MissionManagerLog) << "_updateMissionIndex currentIndex:" << index;
236 _currentMissionIndex = index;
238 }
239
240 if (_currentMissionIndex != _lastCurrentIndex && _cachedLastCurrentIndex != _currentMissionIndex) {
241 // We have to be careful of an RTL sequence causing a change of index to the DO_LAND_START sequence. This also triggers
242 // a flight mode change away from mission flight mode. So we only update _lastCurrentIndex when the flight mode is mission.
243 // But we can run into problems where we may get the MISSION_CURRENT message for the RTL/DO_LAND_START sequenc change prior
244 // to the HEARTBEAT message which contains the flight mode change which will cause things to work incorrectly. To fix this
245 // We force the sequencing of HEARTBEAT following by MISSION_CURRENT by caching the possible _lastCurrentIndex update until
246 // the next HEARTBEAT comes through.
247 qCDebug(MissionManagerLog) << "_updateMissionIndex caching _lastCurrentIndex for possible update:" << _currentMissionIndex;
248 _cachedLastCurrentIndex = _currentMissionIndex;
249 }
250}
251
252void MissionManager::_handleHighLatency(const mavlink_message_t& message)
253{
254 mavlink_high_latency_t highLatency;
255 mavlink_msg_high_latency_decode(&message, &highLatency);
256 _updateMissionIndex(highLatency.wp_num);
257}
258
259void MissionManager::_handleHighLatency2(const mavlink_message_t& message)
260{
261 mavlink_high_latency2_t highLatency2;
262 mavlink_msg_high_latency2_decode(&message, &highLatency2);
263 _updateMissionIndex(highLatency2.wp_num);
264}
265
266void MissionManager::_handleMissionCurrent(const mavlink_message_t& message)
267{
268 mavlink_mission_current_t missionCurrent;
269 mavlink_msg_mission_current_decode(&message, &missionCurrent);
270 _updateMissionIndex(missionCurrent.seq);
271}
272
273void MissionManager::_handleHeartbeat(const mavlink_message_t& message)
274{
275 Q_UNUSED(message);
276
277 if (_cachedLastCurrentIndex != -1 && _vehicle->flightMode() == _vehicle->missionFlightMode()) {
278 qCDebug(MissionManagerLog) << "_handleHeartbeat updating lastCurrentIndex from cached value:" << _cachedLastCurrentIndex;
279 _lastCurrentIndex = _cachedLastCurrentIndex;
280 _cachedLastCurrentIndex = -1;
282 }
283}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
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
Definition MissionItem.h:49
void setIsCurrentItem(bool isCurrentItem)
double param3(void) const
Definition MissionItem.h:56
void setSequenceNumber(int sequenceNumber)
void generateResumeMission(int resumeIndex)
void writeArduPilotGuidedMissionItem(const QGeoCoordinate &gotoCoord, bool altChangeOnly)
int _currentMissionIndex
bool _resumeMission
QList< MissionItem * > _missionItems
Set of mission items on vehicle.
TransactionType_t _transactionInProgress
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void _clearAndDeleteWriteMissionItems(void)
int _lastCurrentIndex
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.
Definition PlanManager.h:93
Vehicle * _vehicle
WeakLinkInterfacePtr primaryLink() const
QGCMAVLink::VehicleClass_t vehicleClass(void) const
Definition Vehicle.h:429
QString missionFlightMode() const
Definition Vehicle.cc:3436
QString flightMode() const
Definition Vehicle.cc:1549
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)
int defaultComponentId() const
Definition Vehicle.h:711