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