QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkMissionItemHandler.cc
Go to the documentation of this file.
2
3#include "MAVLinkProtocol.h"
4#include "MockLink.h"
6
7QGC_LOGGING_CATEGORY(MockLinkMissionItemHandlerLog, "Comms.MockLink.MockLinkMissionItemHandler")
8
10 : QObject(mockLink)
11 , _mockLink(mockLink)
12{
13 // qCDebug(MockLinkMissionItemHandlerLog) << Q_FUNC_INFO << this;
14
15 Q_ASSERT(mockLink);
16
17 (void) connect(&_missionItemResponseTimer, &QTimer::timeout, this, &MockLinkMissionItemHandler::_missionItemResponseTimeout);
18}
19
21{
22 // qCDebug(MockLinkMissionItemHandlerLog) << Q_FUNC_INFO << this;
23}
24
25void MockLinkMissionItemHandler::_startMissionItemResponseTimer()
26{
27 _missionItemResponseTimer.start(500);
28}
29
31{
32 switch (msg.msgid) {
33 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
34 _handleMissionRequestList(msg);
35 break;
36 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
37 _handleMissionRequest(msg);
38 break;
39 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
40 _handleMissionItem(msg);
41 break;
42 case MAVLINK_MSG_ID_MISSION_COUNT:
43 _handleMissionCount(msg);
44 break;
45 case MAVLINK_MSG_ID_MISSION_ACK:
46 // Acks are received back for each MISSION_ITEM message
47 break;
48 case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
49 // Sets the currently active mission item
50 break;
51 case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
52 _handleMissionClearAll(msg);
53 break;
54 default:
55 return false;
56 }
57
58 return true;
59}
60
61void MockLinkMissionItemHandler::_handleMissionClearAll(const mavlink_message_t &msg)
62{
63 mavlink_mission_clear_all_t clearAll{};
64 mavlink_msg_mission_clear_all_decode(&msg, &clearAll);
65
66 Q_ASSERT(clearAll.target_system == _mockLink->vehicleId());
67
68 _requestType = static_cast<MAV_MISSION_TYPE>(clearAll.mission_type);
69 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionClearAll" << _requestType;
70
71 switch (_requestType) {
72 case MAV_MISSION_TYPE_MISSION:
73 _missionItems.clear();
74 break;
75 case MAV_MISSION_TYPE_FENCE:
76 _fenceItems.clear();
77 break;
78 case MAV_MISSION_TYPE_RALLY:
79 _rallyItems.clear();
80 break;
81 case MAV_MISSION_TYPE_ALL:
82 _missionItems.clear();
83 _fenceItems.clear();
84 _rallyItems.clear();
85 break;
86 default:
87 Q_ASSERT(false);
88 }
89
90 _sendAck(MAV_MISSION_ACCEPTED);
91}
92
93void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message_t &msg)
94{
95 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList read sequence";
96
97 _failReadRequest1FirstResponse = true;
98
99 mavlink_mission_request_list_t request{};
100 mavlink_msg_mission_request_list_decode(&msg, &request);
101
102 if (_failureMode == FailReadRequestListNoResponse) {
103 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListNoResponse";
104 return;
105 }
106
107 if ((_failureMode == FailReadRequestListFirstResponse) && _failReadRequestListFirstResponse) {
108 _failReadRequestListFirstResponse = false;
109 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListFirstResponse";
110 return;
111 }
112
113 _failReadRequestListFirstResponse = true;
114
115 Q_ASSERT(request.target_system == _mockLink->vehicleId());
116 _requestListCounts[static_cast<MAV_MISSION_TYPE>(request.mission_type)]++;
117
118 _requestType = static_cast<MAV_MISSION_TYPE>(request.mission_type);
119
120 int itemCount;
121 switch (_requestType) {
122 case MAV_MISSION_TYPE_MISSION:
123 itemCount = _missionItems.count();
124 if (itemCount == 0 && _sendHomePositionOnEmptyList) {
125 itemCount = 1;
126 }
127 break;
128 case MAV_MISSION_TYPE_FENCE:
129 itemCount = _fenceItems.count();
130 break;
131 case MAV_MISSION_TYPE_RALLY:
132 itemCount = _rallyItems.count();
133 break;
134 default:
135 Q_ASSERT(false);
136 }
137
138 mavlink_message_t responseMsg{};
139 (void) mavlink_msg_mission_count_pack_chan(
140 _mockLink->vehicleId(),
141 MAV_COMP_ID_AUTOPILOT1,
142 _mockLink->mavlinkChannel(),
143 &responseMsg, // Outgoing message
144 msg.sysid, // Target is original sender
145 msg.compid, // Target is original sender
146 itemCount, // Number of mission items
147 _requestType,
148 0
149 );
150
151 _mockLink->respondWithMavlinkMessage(responseMsg);
152}
153
154void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t &msg)
155{
156 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest read sequence";
157
158 mavlink_mission_request_int_t request{};
159 mavlink_msg_mission_request_int_decode(&msg, &request);
160
161 Q_ASSERT(request.target_system == _mockLink->vehicleId());
162
163 if ((_failureMode == FailReadRequest0NoResponse) && (request.seq == 0)) {
164 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest0NoResponse";
165 return;
166 }
167
168 if ((_failureMode == FailReadRequest1NoResponse) && (request.seq == 1)) {
169 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1NoResponse";
170 return;
171 }
172
173 if ((_failureMode == FailReadRequest1FirstResponse) && (request.seq == 1) && _failReadRequest1FirstResponse) {
174 _failReadRequest1FirstResponse = false;
175 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1FirstResponse";
176 return;
177 }
178
179 // FIXME: Track whether all items are requested, or requested in sequence
180
181 if (((_failureMode == FailReadRequest0IncorrectSequence) && (request.seq == 0)) ||
182 ((_failureMode == FailReadRequest1IncorrectSequence) && (request.seq == 1))) {
183 // Send back the incorrect sequence number
184 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest sending bad sequence number";
185 request.seq++;
186 }
187
188 if (((_failureMode == FailReadRequest0ErrorAck) && (request.seq == 0)) ||
189 ((_failureMode == FailReadRequest1ErrorAck) && (request.seq == 1))) {
190 _sendAck(_failureAckResult);
191 return;
192 }
193
194 mavlink_mission_item_int_t missionItemInt{};
195
196 switch (request.mission_type) {
197 case MAV_MISSION_TYPE_MISSION:
198 if (_missionItems.isEmpty() && _sendHomePositionOnEmptyList) {
199 (void) memset(&missionItemInt, 0, sizeof(missionItemInt));
200 missionItemInt.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
201 missionItemInt.command = MAV_CMD_NAV_WAYPOINT;
202 missionItemInt.autocontinue = true;
203 } else {
204 missionItemInt = _missionItems[request.seq];
205 }
206 break;
207 case MAV_MISSION_TYPE_FENCE:
208 missionItemInt = _fenceItems[request.seq];
209 break;
210 case MAV_MISSION_TYPE_RALLY:
211 missionItemInt = _rallyItems[request.seq];
212 break;
213 default:
214 Q_ASSERT(false);
215 }
216
217 mavlink_message_t responseMsg{};
218 (void) mavlink_msg_mission_item_int_pack_chan(
219 _mockLink->vehicleId(),
220 MAV_COMP_ID_AUTOPILOT1,
221 _mockLink->mavlinkChannel(),
222 &responseMsg, // Outgoing message
223 msg.sysid, // Target is original sender
224 msg.compid, // Target is original sender
225 request.seq, // Index of mission item being sent
226 missionItemInt.frame,
227 missionItemInt.command,
228 missionItemInt.current,
229 missionItemInt.autocontinue,
230 missionItemInt.param1, missionItemInt.param2, missionItemInt.param3, missionItemInt.param4,
231 missionItemInt.x, missionItemInt.y, missionItemInt.z,
232 _requestType
233 );
234
235 _mockLink->respondWithMavlinkMessage(responseMsg);
236}
237
238void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t &msg)
239{
240 mavlink_mission_count_t missionCount{};
241 mavlink_msg_mission_count_decode(&msg, &missionCount);
242 Q_ASSERT(missionCount.target_system == _mockLink->vehicleId());
243
244 _requestType = (MAV_MISSION_TYPE)missionCount.mission_type;
245 _writeSequenceCount = missionCount.count;
246 Q_ASSERT(_writeSequenceCount >= 0);
247
248 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
249
250 switch (missionCount.mission_type) {
251 case MAV_MISSION_TYPE_MISSION:
252 _missionItems.clear();
253 break;
254 case MAV_MISSION_TYPE_FENCE:
255 _fenceItems.clear();
256 break;
257 case MAV_MISSION_TYPE_RALLY:
258 _rallyItems.clear();
259 break;
260 }
261
262 if (_writeSequenceCount == 0) {
263 _sendAck(MAV_MISSION_ACCEPTED);
264 return;
265 }
266
267 if (_failureMode == FailWriteMissionCountNoResponse) {
268 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
269 return;
270 }
271
272 if (_failureMode == FailWriteMissionCountFirstResponse && _failWriteMissionCountFirstResponse) {
273 _failWriteMissionCountFirstResponse = false;
274 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
275 return;
276 }
277
278 _failWriteMissionCountFirstResponse = true;
279 _writeSequenceIndex = 0;
280 _requestNextMissionItem(_writeSequenceIndex);
281}
282
283void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
284{
285 qCDebug(MockLinkMissionItemHandlerLog) << "write sequence sequenceNumber:" << sequenceNumber << "_failureMode:" << _failureMode;
286
287 if ((_failureMode == FailWriteRequest1NoResponse) && (sequenceNumber == 1)) {
288 qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem not responding due to failure mode FailWriteRequest1NoResponse";
289 return;
290 }
291
292 if (sequenceNumber >= _writeSequenceCount) {
293 qCWarning(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
294 return;
295 }
296
297 if (((_failureMode == FailWriteRequest0IncorrectSequence) && (sequenceNumber == 0)) ||
298 ((_failureMode == FailWriteRequest1IncorrectSequence) && (sequenceNumber == 1))) {
299 sequenceNumber++;
300 }
301
302 if (((_failureMode == FailWriteRequest0ErrorAck) && (sequenceNumber == 0)) ||
303 ((_failureMode == FailWriteRequest1ErrorAck) && (sequenceNumber == 1))) {
304 qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem sending ack error due to failure mode";
305 _sendAck(_failureAckResult);
306 return;
307 }
308
309 mavlink_message_t message{};
310 (void) mavlink_msg_mission_request_int_pack_chan(
311 _mockLink->vehicleId(),
312 MAV_COMP_ID_AUTOPILOT1,
313 _mockLink->mavlinkChannel(),
314 &message,
317 sequenceNumber,
318 _requestType
319 );
320 _mockLink->respondWithMavlinkMessage(message);
321
322 // If response with Mission Item doesn't come before timer fires it's an error
323 _startMissionItemResponseTimer();
324}
325
326void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) const
327{
328 qCDebug(MockLinkMissionItemHandlerLog) << "_sendAck write sequence complete ackType:" << ackType;
329
330 mavlink_message_t message{};
331 (void) mavlink_msg_mission_ack_pack_chan(
332 _mockLink->vehicleId(),
333 MAV_COMP_ID_AUTOPILOT1,
334 _mockLink->mavlinkChannel(),
335 &message,
338 ackType,
339 _requestType,
340 0
341 );
342
343 _mockLink->respondWithMavlinkMessage(message);
344}
345
346void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t &msg)
347{
348 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionItem write sequence";
349
350 _missionItemResponseTimer.stop();
351
352 mavlink_mission_item_int_t missionItemInt{};
353 mavlink_msg_mission_item_int_decode(&msg, &missionItemInt);
354
355 const MAV_MISSION_TYPE missionType = static_cast<MAV_MISSION_TYPE>(missionItemInt.mission_type);
356 const uint16_t seq = missionItemInt.seq;
357
358 switch (missionType) {
359 case MAV_MISSION_TYPE_MISSION:
360 _missionItems[seq] = missionItemInt;
361 break;
362 case MAV_MISSION_TYPE_FENCE:
363 _fenceItems[seq] = missionItemInt;
364 break;
365 case MAV_MISSION_TYPE_RALLY:
366 _rallyItems[seq] = missionItemInt;
367 break;
368 case MAV_MISSION_TYPE_ENUM_END:
369 case MAV_MISSION_TYPE_ALL:
370 qCWarning(MockLinkMissionItemHandlerLog) << "Internal error";
371 break;
372 }
373
374 _writeSequenceIndex++;
375 if (_writeSequenceIndex < _writeSequenceCount) {
376 if ((_failureMode == FailWriteFinalAckMissingRequests) && (_writeSequenceIndex == 3)) {
377 // Send MAV_MISSION_ACCEPTED ack too early
378 _sendAck(MAV_MISSION_ACCEPTED);
379 } else {
380 _requestNextMissionItem(_writeSequenceIndex);
381 }
382
383 return;
384 }
385
386 if (_failureMode != FailWriteFinalAckNoResponse) {
387 MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
388
389 if (_failureMode == FailWriteFinalAckErrorAck) {
390 ack = MAV_MISSION_ERROR;
391 }
392
393 _sendAck(ack);
394 }
395}
396
397void MockLinkMissionItemHandler::_missionItemResponseTimeout()
398{
399 qCWarning(MockLinkMissionItemHandlerLog) << "Timeout waiting for next MISSION_ITEM_INT";
400 Q_ASSERT(false);
401}
402
404{
405 _sendAck(ackType);
406}
407
409{
410 // FIXME: NYI
411 Q_ASSERT(false);
412}
413
415{
416 // FIXME: NYI
417 Q_ASSERT(false);
418}
419
420void MockLinkMissionItemHandler::setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
421{
422 _failureMode = failureMode;
423 _failureAckResult = failureAckResult;
424}
425
427{
428 _missionItemResponseTimer.stop();
429}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
void sendUnexpectedMissionAck(MAV_MISSION_RESULT ackType)
Called to send a MISSION_ACK message while the MissionManager is in idle state.
bool handleMavlinkMessage(const mavlink_message_t &msg)
void setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
void sendUnexpectedMissionRequest()
Called to send a MISSION_REQUEST message while the MissionManager is in idle state.
void sendUnexpectedMissionItem()
Called to send a MISSION_ITEM message while the MissionManager is in idle state.