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 if (_failureMode == FailReadRequestListNoResponse) {
100 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListNoResponse";
101 return;
102 }
103
104 if ((_failureMode == FailReadRequestListFirstResponse) && _failReadRequestListFirstResponse) {
105 _failReadRequestListFirstResponse = false;
106 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode FailReadRequestListFirstResponse";
107 return;
108 }
109
110 _failReadRequestListFirstResponse = true;
111
112 mavlink_mission_request_list_t request{};
113 mavlink_msg_mission_request_list_decode(&msg, &request);
114
115 Q_ASSERT(request.target_system == _mockLink->vehicleId());
116
117 _requestType = static_cast<MAV_MISSION_TYPE>(request.mission_type);
118
119 int itemCount;
120 switch (_requestType) {
121 case MAV_MISSION_TYPE_MISSION:
122 itemCount = _missionItems.count();
123 if (itemCount == 0 && _sendHomePositionOnEmptyList) {
124 itemCount = 1;
125 }
126 break;
127 case MAV_MISSION_TYPE_FENCE:
128 itemCount = _fenceItems.count();
129 break;
130 case MAV_MISSION_TYPE_RALLY:
131 itemCount = _rallyItems.count();
132 break;
133 default:
134 Q_ASSERT(false);
135 }
136
137 mavlink_message_t responseMsg{};
138 (void) mavlink_msg_mission_count_pack_chan(
139 _mockLink->vehicleId(),
140 MAV_COMP_ID_AUTOPILOT1,
141 _mockLink->mavlinkChannel(),
142 &responseMsg, // Outgoing message
143 msg.sysid, // Target is original sender
144 msg.compid, // Target is original sender
145 itemCount, // Number of mission items
146 _requestType,
147 0
148 );
149
150 _mockLink->respondWithMavlinkMessage(responseMsg);
151}
152
153void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t &msg)
154{
155 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest read sequence";
156
157 mavlink_mission_request_int_t request{};
158 mavlink_msg_mission_request_int_decode(&msg, &request);
159
160 Q_ASSERT(request.target_system == _mockLink->vehicleId());
161
162 if ((_failureMode == FailReadRequest0NoResponse) && (request.seq == 0)) {
163 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest0NoResponse";
164 return;
165 }
166
167 if ((_failureMode == FailReadRequest1NoResponse) && (request.seq == 1)) {
168 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1NoResponse";
169 return;
170 }
171
172 if ((_failureMode == FailReadRequest1FirstResponse) && (request.seq == 1) && _failReadRequest1FirstResponse) {
173 _failReadRequest1FirstResponse = false;
174 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest not responding due to failure mode FailReadRequest1FirstResponse";
175 return;
176 }
177
178 // FIXME: Track whether all items are requested, or requested in sequence
179
180 if (((_failureMode == FailReadRequest0IncorrectSequence) && (request.seq == 0)) ||
181 ((_failureMode == FailReadRequest1IncorrectSequence) && (request.seq == 1))) {
182 // Send back the incorrect sequence number
183 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequest sending bad sequence number";
184 request.seq++;
185 }
186
187 if (((_failureMode == FailReadRequest0ErrorAck) && (request.seq == 0)) ||
188 ((_failureMode == FailReadRequest1ErrorAck) && (request.seq == 1))) {
189 _sendAck(_failureAckResult);
190 return;
191 }
192
193 mavlink_mission_item_int_t missionItemInt{};
194
195 switch (request.mission_type) {
196 case MAV_MISSION_TYPE_MISSION:
197 if (_missionItems.isEmpty() && _sendHomePositionOnEmptyList) {
198 (void) memset(&missionItemInt, 0, sizeof(missionItemInt));
199 missionItemInt.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
200 missionItemInt.command = MAV_CMD_NAV_WAYPOINT;
201 missionItemInt.autocontinue = true;
202 } else {
203 missionItemInt = _missionItems[request.seq];
204 }
205 break;
206 case MAV_MISSION_TYPE_FENCE:
207 missionItemInt = _fenceItems[request.seq];
208 break;
209 case MAV_MISSION_TYPE_RALLY:
210 missionItemInt = _rallyItems[request.seq];
211 break;
212 default:
213 Q_ASSERT(false);
214 }
215
216 mavlink_message_t responseMsg{};
217 (void) mavlink_msg_mission_item_int_pack_chan(
218 _mockLink->vehicleId(),
219 MAV_COMP_ID_AUTOPILOT1,
220 _mockLink->mavlinkChannel(),
221 &responseMsg, // Outgoing message
222 msg.sysid, // Target is original sender
223 msg.compid, // Target is original sender
224 request.seq, // Index of mission item being sent
225 missionItemInt.frame,
226 missionItemInt.command,
227 missionItemInt.current,
228 missionItemInt.autocontinue,
229 missionItemInt.param1, missionItemInt.param2, missionItemInt.param3, missionItemInt.param4,
230 missionItemInt.x, missionItemInt.y, missionItemInt.z,
231 _requestType
232 );
233
234 _mockLink->respondWithMavlinkMessage(responseMsg);
235}
236
237void MockLinkMissionItemHandler::_handleMissionCount(const mavlink_message_t &msg)
238{
239 mavlink_mission_count_t missionCount{};
240 mavlink_msg_mission_count_decode(&msg, &missionCount);
241 Q_ASSERT(missionCount.target_system == _mockLink->vehicleId());
242
243 _requestType = (MAV_MISSION_TYPE)missionCount.mission_type;
244 _writeSequenceCount = missionCount.count;
245 Q_ASSERT(_writeSequenceCount >= 0);
246
247 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount write sequence _writeSequenceCount:" << _writeSequenceCount;
248
249 switch (missionCount.mission_type) {
250 case MAV_MISSION_TYPE_MISSION:
251 _missionItems.clear();
252 break;
253 case MAV_MISSION_TYPE_FENCE:
254 _fenceItems.clear();
255 break;
256 case MAV_MISSION_TYPE_RALLY:
257 _rallyItems.clear();
258 break;
259 }
260
261 if (_writeSequenceCount == 0) {
262 _sendAck(MAV_MISSION_ACCEPTED);
263 return;
264 }
265
266 if (_failureMode == FailWriteMissionCountNoResponse) {
267 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
268 return;
269 }
270
271 if (_failureMode == FailWriteMissionCountFirstResponse && _failWriteMissionCountFirstResponse) {
272 _failWriteMissionCountFirstResponse = false;
273 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionCount not responding due to failure mode FailWriteMissionCountNoResponse";
274 return;
275 }
276
277 _failWriteMissionCountFirstResponse = true;
278 _writeSequenceIndex = 0;
279 _requestNextMissionItem(_writeSequenceIndex);
280}
281
282void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
283{
284 qCDebug(MockLinkMissionItemHandlerLog) << "write sequence sequenceNumber:" << sequenceNumber << "_failureMode:" << _failureMode;
285
286 if ((_failureMode == FailWriteRequest1NoResponse) && (sequenceNumber == 1)) {
287 qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem not responding due to failure mode FailWriteRequest1NoResponse";
288 return;
289 }
290
291 if (sequenceNumber >= _writeSequenceCount) {
292 qCWarning(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem requested seqeuence number > write count sequenceNumber::_writeSequenceCount" << sequenceNumber << _writeSequenceCount;
293 return;
294 }
295
296 if (((_failureMode == FailWriteRequest0IncorrectSequence) && (sequenceNumber == 0)) ||
297 ((_failureMode == FailWriteRequest1IncorrectSequence) && (sequenceNumber == 1))) {
298 sequenceNumber++;
299 }
300
301 if (((_failureMode == FailWriteRequest0ErrorAck) && (sequenceNumber == 0)) ||
302 ((_failureMode == FailWriteRequest1ErrorAck) && (sequenceNumber == 1))) {
303 qCDebug(MockLinkMissionItemHandlerLog) << "_requestNextMissionItem sending ack error due to failure mode";
304 _sendAck(_failureAckResult);
305 return;
306 }
307
308 mavlink_message_t message{};
309 (void) mavlink_msg_mission_request_int_pack_chan(
310 _mockLink->vehicleId(),
311 MAV_COMP_ID_AUTOPILOT1,
312 _mockLink->mavlinkChannel(),
313 &message,
316 sequenceNumber,
317 _requestType
318 );
319 _mockLink->respondWithMavlinkMessage(message);
320
321 // If response with Mission Item doesn't come before timer fires it's an error
322 _startMissionItemResponseTimer();
323}
324
325void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) const
326{
327 qCDebug(MockLinkMissionItemHandlerLog) << "_sendAck write sequence complete ackType:" << ackType;
328
329 mavlink_message_t message{};
330 (void) mavlink_msg_mission_ack_pack_chan(
331 _mockLink->vehicleId(),
332 MAV_COMP_ID_AUTOPILOT1,
333 _mockLink->mavlinkChannel(),
334 &message,
337 ackType,
338 _requestType,
339 0
340 );
341
342 _mockLink->respondWithMavlinkMessage(message);
343}
344
345void MockLinkMissionItemHandler::_handleMissionItem(const mavlink_message_t &msg)
346{
347 qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionItem write sequence";
348
349 _missionItemResponseTimer.stop();
350
351 mavlink_mission_item_int_t missionItemInt{};
352 mavlink_msg_mission_item_int_decode(&msg, &missionItemInt);
353
354 const MAV_MISSION_TYPE missionType = static_cast<MAV_MISSION_TYPE>(missionItemInt.mission_type);
355 const uint16_t seq = missionItemInt.seq;
356
357 switch (missionType) {
358 case MAV_MISSION_TYPE_MISSION:
359 _missionItems[seq] = missionItemInt;
360 break;
361 case MAV_MISSION_TYPE_FENCE:
362 _fenceItems[seq] = missionItemInt;
363 break;
364 case MAV_MISSION_TYPE_RALLY:
365 _rallyItems[seq] = missionItemInt;
366 break;
367 case MAV_MISSION_TYPE_ENUM_END:
368 case MAV_MISSION_TYPE_ALL:
369 qCWarning(MockLinkMissionItemHandlerLog) << "Internal error";
370 break;
371 }
372
373 _writeSequenceIndex++;
374 if (_writeSequenceIndex < _writeSequenceCount) {
375 if ((_failureMode == FailWriteFinalAckMissingRequests) && (_writeSequenceIndex == 3)) {
376 // Send MAV_MISSION_ACCEPTED ack too early
377 _sendAck(MAV_MISSION_ACCEPTED);
378 } else {
379 _requestNextMissionItem(_writeSequenceIndex);
380 }
381
382 return;
383 }
384
385 if (_failureMode != FailWriteFinalAckNoResponse) {
386 MAV_MISSION_RESULT ack = MAV_MISSION_ACCEPTED;
387
388 if (_failureMode == FailWriteFinalAckErrorAck) {
389 ack = MAV_MISSION_ERROR;
390 }
391
392 _sendAck(ack);
393 }
394}
395
396void MockLinkMissionItemHandler::_missionItemResponseTimeout()
397{
398 qCWarning(MockLinkMissionItemHandlerLog) << "Timeout waiting for next MISSION_ITEM_INT";
399 Q_ASSERT(false);
400}
401
403{
404 _sendAck(ackType);
405}
406
408{
409 // FIXME: NYI
410 Q_ASSERT(false);
411}
412
414{
415 // FIXME: NYI
416 Q_ASSERT(false);
417}
418
419void MockLinkMissionItemHandler::setFailureMode(FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
420{
421 _failureMode = failureMode;
422 _failureAckResult = failureAckResult;
423}
424
426{
427 _missionItemResponseTimer.stop();
428}
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
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.