QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkFTP.cc
Go to the documentation of this file.
1#include "MockLinkFTP.h"
2#include "MockLink.h"
4
5#include <QtCore/QDataStream>
6#include <QtCore/QDir>
7#include <QtCore/QTemporaryFile>
8
9QGC_LOGGING_CATEGORY(MockLinkFTPLog, "Comms.MockLink.MockLinkFTP")
10
11MockLinkFTP::MockLinkFTP(uint8_t systemIdServer, uint8_t componentIdServer, MockLink *mockLink)
12 : QObject(mockLink)
13 , _systemIdServer(systemIdServer)
14 , _componentIdServer(componentIdServer)
15 , _mockLink(mockLink)
16{
17 // qCDebug(MockLinkFTPLog) << Q_FUNC_INFO << this;
18}
19
21{
22 if (!_paramPckTempFile.isEmpty()) {
23 QFile::remove(_paramPckTempFile);
24 }
25}
26
27void MockLinkFTP::ensureNullTemination(MavlinkFTP::Request *request)
28{
29 if (request->hdr.size < sizeof(request->data)) {
30 request->data[request->hdr.size] = '\0';
31 } else {
32 request->data[sizeof(request->data) - 1] = '\0';
33 }
34}
35
36void MockLinkFTP::_listCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
37{
38 MavlinkFTP::Request ackResponse{};
39 ensureNullTemination(request);
40
41 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
42
43 // We only support root path
44 const QString path = reinterpret_cast<char*>(&request->data[0]);
45 if (!path.isEmpty() && path != "/") {
46 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
47 return;
48 }
49
50 if (request->hdr.offset > 0) {
51 if (_errMode == errModeNakSecondResponse) {
52 // Nak error all subsequent requests
53 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
54 return;
55 }
56
57 if (_errMode == errModeNoSecondResponse) {
58 // No response for all subsequent requests
59 return;
60 }
61
62 if (_errMode == errModeNoSecondResponseAllowRetry) {
63 // No response to this request, subsequent requests will succeed
64 _errMode = errModeNone;
65 return;
66 }
67 }
68
69 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
70 ackResponse.hdr.req_opcode = MavlinkFTP::kCmdListDirectory;
71 ackResponse.hdr.session = 0;
72 ackResponse.hdr.offset = request->hdr.offset;
73 ackResponse.hdr.size = 0;
74
75 // MockLink sends two directory entries per packet for a maximum of 3 packets, 6 total entries
76 if (request->hdr.offset <= 5) {
77 char *bufPtr = reinterpret_cast<char*>(&ackResponse.data[0]);
78 QString dirEntry = QStringLiteral("Ffile%1.txt").arg(request->hdr.offset);
79 auto cchDirEntry = dirEntry.length();
80 (void) strncpy(bufPtr, dirEntry.toStdString().c_str(), cchDirEntry);
81 ackResponse.hdr.size += dirEntry.length() + 1;
82 bufPtr += cchDirEntry + 1;
83 dirEntry = QStringLiteral("Ffile%1.txt").arg(request->hdr.offset + 1);
84 cchDirEntry = dirEntry.length();
85 (void) strncpy(bufPtr, dirEntry.toStdString().c_str(), cchDirEntry);
86 ackResponse.hdr.size += dirEntry.length() + 1;
87 } else {
88 ackResponse.hdr.opcode = MavlinkFTP::kRspNak;
89 ackResponse.data[0] = MavlinkFTP::kErrEOF;
90 ackResponse.hdr.size = 1;
91 }
92
93 _sendResponse(senderSystemId, senderComponentId, &ackResponse, outgoingSeqNumber);
94}
95
96void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
97{
98 MavlinkFTP::Request response{};
99 ensureNullTemination(request);
100 const QString path = reinterpret_cast<char*>(request->data);
101
102 _uploadSession.reset();
103
104 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
105
106 const size_t cchPath = strnlen(reinterpret_cast<char*>(request->data), sizeof(request->data));
107 Q_ASSERT(cchPath != sizeof(request->data));
108 Q_UNUSED(cchPath); // Fix initialized-but-not-referenced warning on release builds
109
110 _currentFile.close();
111
112 QString tmpFilename;
113 const QString sizePrefix = sizeFilenamePrefix;
114 if (path.startsWith(sizePrefix)) {
115 const QString sizeString = path.right(path.length() - sizePrefix.length());
116 tmpFilename = _createTestTempFile(sizeString.toInt());
117 } else if (path == "/general.json") {
118 tmpFilename = QStringLiteral(":MockLink/General.MetaData.json");
119 } else if (path == "/general.json.xz") {
120 tmpFilename = QStringLiteral(":MockLink/General.MetaData.json.xz");
121 } else if (path == "/parameter.json") {
122 tmpFilename = QStringLiteral(":MockLink/Parameter.MetaData.json");
123 } else if (path == "/parameter.json.xz") {
124 tmpFilename = QStringLiteral(":MockLink/Parameter.MetaData.json.xz");
125 } else if (path == "@PARAM/param.pck" || path.startsWith("@PARAM/param.pck?")) {
126 const bool withDefaults = path.contains(QStringLiteral("withdefaults=1"));
127 tmpFilename = _generateParamPck(withDefaults);
128 }
129
130 if (!tmpFilename.isEmpty()) {
131 _currentFile.setFileName(tmpFilename);
132 if (!_currentFile.open(QIODevice::ReadOnly)) {
133 _sendNakErrno(senderSystemId, senderComponentId, _currentFile.error(), outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
134 return;
135 }
136 } else {
137 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFailFileNotFound, outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
138 return;
139 }
140
141 response.hdr.opcode = MavlinkFTP::kRspAck;
142 response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileRO;
143 response.hdr.session = _sessionId;
144
145 // Data contains file length
146 response.hdr.size = sizeof(uint32_t);
147
148 // Ardupilot sends constant wrong file size for parameter file due to dynamic on the fly generation
149 response.openFileLength = ((path == "@PARAM/param.pck" || path.startsWith("@PARAM/param.pck?")) ? qPow(1024, 2) : _currentFile.size());
150
151 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
152}
153
154void MockLinkFTP::_createFileCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
155{
156 ensureNullTemination(request);
157
158 const QString path = reinterpret_cast<char*>(request->data);
159 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
160
161 if (path.isEmpty()) {
162 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdCreateFile);
163 return;
164 }
165
166 _uploadSession.reset();
167 _uploadSession.active = true;
168 _uploadSession.remotePath = path;
169
170 MavlinkFTP::Request response{};
171 response.hdr.opcode = MavlinkFTP::kRspAck;
172 response.hdr.req_opcode = MavlinkFTP::kCmdCreateFile;
173 response.hdr.session = _sessionId;
174 response.hdr.size = 0;
175
176 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
177}
178
179void MockLinkFTP::_openFileWOCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
180{
181 ensureNullTemination(request);
182
183 const QString path = reinterpret_cast<char*>(request->data);
184 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
185
186 if (path.isEmpty()) {
187 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdOpenFileWO);
188 return;
189 }
190
191 _uploadSession.reset();
192 _uploadSession.active = true;
193 _uploadSession.remotePath = path;
194
195 MavlinkFTP::Request response{};
196 response.hdr.opcode = MavlinkFTP::kRspAck;
197 response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileWO;
198 response.hdr.session = _sessionId;
199 response.hdr.size = 0;
200
201 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
202}
203
204void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
205{
206 MavlinkFTP::Request response{};
207 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
208
209 if (request->hdr.session != _sessionId) {
210 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
211 return;
212 }
213
214 const uint32_t readOffset = request->hdr.offset; // offset into file for reading
215 if (readOffset != 0) {
216 // If we get here it means the client is requesting additional data past the first request
217 if (_errMode == errModeNakSecondResponse) {
218 // Nak error all subsequent requests
219 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
220 return;
221 }
222
223 if (_errMode == errModeNoSecondResponse) {
224 // No rsponse for all subsequent requests
225 return;
226 }
227 }
228
229 if (readOffset >= _currentFile.size()) {
230 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
231 return;
232 }
233
234 const uint8_t cBytesToRead = static_cast<uint8_t>(qMin(static_cast<qint64>(sizeof(response.data)), _currentFile.size() - readOffset));
235 (void) _currentFile.seek(readOffset);
236 const QByteArray bytes = _currentFile.read(cBytesToRead);
237 (void) memcpy(response.data, bytes.constData(), cBytesToRead);
238
239 // We should always have written something, otherwise there is something wrong with the code above
240 Q_ASSERT(cBytesToRead);
241
242 response.hdr.session = _sessionId;
243 response.hdr.size = cBytesToRead;
244 response.hdr.offset = request->hdr.offset;
245 response.hdr.opcode = MavlinkFTP::kRspAck;
246 response.hdr.req_opcode = MavlinkFTP::kCmdReadFile;
247
248 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
249}
250
251void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
252{
253 MavlinkFTP::Request response{};
254 uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
255
256 if (request->hdr.session != _sessionId) {
257 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
258 return;
259 }
260
261 constexpr int burstMax = 10;
262 int burstCount = 1;
263 uint32_t burstOffset = request->hdr.offset;
264
265 while ((burstOffset < _currentFile.size()) && (burstCount++ < burstMax)) {
266 _currentFile.seek(burstOffset);
267
268 const uint8_t cBytes = static_cast<uint8_t>(qMin(static_cast<qint64>(sizeof(response.data)), _currentFile.size() - burstOffset));
269 const QByteArray bytes = _currentFile.read(cBytes);
270 Q_ASSERT(cBytes); // We should always have written something, otherwise there is something wrong with the code above
271
272 (void) memcpy(response.data, bytes.constData(), cBytes);
273
274 response.hdr.session = _sessionId;
275 response.hdr.size = cBytes;
276 response.hdr.offset = burstOffset;
277 response.hdr.opcode = MavlinkFTP::kRspAck;
278 response.hdr.req_opcode = MavlinkFTP::kCmdBurstReadFile;
279 response.hdr.burstComplete = (burstCount == burstMax) ? 1 : 0;
280
281 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
282
283 outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
284 burstOffset += cBytes;
285 }
286
287 if (burstOffset >= _currentFile.size()) {
288 // Burst is fully complete
289 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
290 }
291}
292
293void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
294{
295 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
296
297 if (request->hdr.session != _sessionId) {
298 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
299 return;
300 }
301
302 _currentFile.close();
303 _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
304
305 _finalizeActiveUpload();
306
308}
309
310void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber)
311{
312 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
313
314 _currentFile.close();
315 _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdResetSessions);
316
317 _finalizeActiveUpload();
318
320}
321
322void MockLinkFTP::_writeCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
323{
324 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
325
326 if ((request->hdr.session != _sessionId) || !_uploadSession.active) {
327 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
328 return;
329 }
330
331 if (request->hdr.offset > static_cast<uint32_t>(_uploadSession.buffer.size())) {
332 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
333 return;
334 }
335
336 if (request->hdr.offset != 0) {
337 if (_errMode == errModeNakSecondResponse) {
338 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
339 return;
340 }
341
342 if (_errMode == errModeNoSecondResponse) {
343 return;
344 }
345
346 if (_errMode == errModeNoSecondResponseAllowRetry) {
347 _errMode = errModeNone;
348 return;
349 }
350 }
351
352 const uint32_t bytesToWrite = request->hdr.size;
353 if (bytesToWrite > sizeof(request->data)) {
354 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
355 return;
356 }
357
358 const uint32_t requiredSize = request->hdr.offset + bytesToWrite;
359 if (requiredSize > static_cast<uint32_t>(_uploadSession.buffer.size())) {
360 _uploadSession.buffer.resize(requiredSize);
361 }
362
363 if (bytesToWrite > 0) {
364 (void) memcpy(_uploadSession.buffer.data() + request->hdr.offset, request->data, bytesToWrite);
365 }
366
367 MavlinkFTP::Request response{};
368 response.hdr.opcode = MavlinkFTP::kRspAck;
369 response.hdr.req_opcode = MavlinkFTP::kCmdWriteFile;
370 response.hdr.session = _sessionId;
371 response.hdr.size = 0;
372 response.hdr.offset = request->hdr.offset;
373
374 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
375}
376
377void MockLinkFTP::_finalizeActiveUpload()
378{
379 if (!_uploadSession.active) {
380 return;
381 }
382
383 if (!_uploadSession.remotePath.isEmpty()) {
384 _uploadedFiles.insert(_uploadSession.remotePath, _uploadSession.buffer);
385 }
386
387 _uploadSession.reset();
388}
389
391{
392 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
393 return;
394 }
395
396 mavlink_file_transfer_protocol_t requestFTP{};
397 mavlink_msg_file_transfer_protocol_decode(&message, &requestFTP);
398
399 if (requestFTP.target_system != _systemIdServer) {
400 return;
401 }
402
403 MavlinkFTP::Request *request = reinterpret_cast<MavlinkFTP::Request*>(&requestFTP.payload[0]);
404
405 // kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
406 if (_randomDropsEnabled && (request->hdr.opcode != MavlinkFTP::kCmdOpenFileRO) && (request->hdr.opcode != MavlinkFTP::kCmdResetSessions)) {
407 if ((rand() % 5) == 0) {
408 qCDebug(MockLinkFTPLog) << "MockLinkFTP: Random drop of incoming packet";
409 return;
410 }
411 }
412
413 if (_lastReplyValid && (request->hdr.seqNumber == (_lastReplySequence - 1))) {
414 // This is the same request as the one we replied to last. It means the (n)ack got lost, and the GCS
415 // resent the request
416 qCDebug(MockLinkFTPLog) << "MockLinkFTP: resending response";
417 _mockLink->respondWithMavlinkMessage(_lastReply);
418 return;
419 }
420
421 const uint16_t incomingSeqNumber = request->hdr.seqNumber;
422 const uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
423
424 if ((request->hdr.opcode != MavlinkFTP::kCmdResetSessions) && (request->hdr.opcode != MavlinkFTP::kCmdTerminateSession)) {
425 if (_errMode == errModeNoResponse) {
426 // Don't respond to any requests, this shold cause the client to eventually timeout waiting for the ack
427 return;
428 }
429
430 if (_errMode == errModeNakResponse) {
431 // Nak all requests, the actual error send back doesn't really matter as long as it's an error
432 _sendNak(message.sysid, message.compid, MavlinkFTP::kErrFail, outgoingSeqNumber, static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));
433 return;
434 }
435 }
436
437 MavlinkFTP::Request ackResponse{};
438 switch (request->hdr.opcode) {
440 // ignored, always acked
441 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
442 ackResponse.hdr.session = 0;
443 ackResponse.hdr.size = 0;
444 _sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
445 break;
447 _listCommand(message.sysid, message.compid, request, incomingSeqNumber);
448 break;
450 _openCommand(message.sysid, message.compid, request, incomingSeqNumber);
451 break;
453 _createFileCommand(message.sysid, message.compid, request, incomingSeqNumber);
454 break;
456 _openFileWOCommand(message.sysid, message.compid, request, incomingSeqNumber);
457 break;
459 _readCommand(message.sysid, message.compid, request, incomingSeqNumber);
460 break;
462 _burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
463 break;
465 _writeCommand(message.sysid, message.compid, request, incomingSeqNumber);
466 break;
468 _terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
469 break;
471 _resetCommand(message.sysid, message.compid, incomingSeqNumber);
472 break;
473 default:
474 // nack for all NYI opcodes
475 _sendNak(message.sysid, message.compid, MavlinkFTP::kErrUnknownCommand, outgoingSeqNumber, static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));
476 break;
477 }
478}
479
480void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
481{
482 MavlinkFTP::Request ackResponse{};
483
484 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
485 ackResponse.hdr.req_opcode = reqOpcode;
486 ackResponse.hdr.session = _sessionId;
487 ackResponse.hdr.size = 0;
488
489 _sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
490}
491
492void MockLinkFTP::_sendNak(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::ErrorCode_t error, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
493{
494 MavlinkFTP::Request nakResponse{};
495
496 nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
497 nakResponse.hdr.req_opcode = reqOpcode;
498 nakResponse.hdr.session = _sessionId;
499 nakResponse.hdr.size = 1;
500 nakResponse.data[0] = error;
501
502 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
503}
504
505void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentId, uint8_t nakErrno, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
506{
507 MavlinkFTP::Request nakResponse{};
508
509 nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
510 nakResponse.hdr.req_opcode = reqOpcode;
511 nakResponse.hdr.session = _sessionId;
512 nakResponse.hdr.size = 2;
513 nakResponse.data[0] = MavlinkFTP::kErrFailErrno;
514 nakResponse.data[1] = nakErrno;
515
516 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
517}
518
519
520void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
521{
522 request->hdr.seqNumber = seqNumber;
523 _lastReplySequence = seqNumber;
524 _lastReplyValid = true;
525
526 (void) mavlink_msg_file_transfer_protocol_pack_chan(
527 _systemIdServer, // System ID
528 _componentIdServer, // Component ID
529 _mockLink->mavlinkChannel(),
530 &_lastReply, // Mavlink Message to pack into
531 0, // Target network
532 targetSystemId,
533 targetComponentId,
534 reinterpret_cast<uint8_t*>(request) // Payload
535 );
536
537 // kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
538 if (_randomDropsEnabled && (request->hdr.req_opcode != MavlinkFTP::kCmdOpenFileRO) && (request->hdr.req_opcode != MavlinkFTP::kCmdResetSessions)) {
539 if ((rand() % 5) == 0) {
540 qCDebug(MockLinkFTPLog) << "MockLinkFTP: Random drop of outgoing packet";
541 return;
542 }
543 }
544
545 _mockLink->respondWithMavlinkMessage(_lastReply);
546}
547
548
549uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber) const
550{
551 uint16_t outgoingSeqNumber = seqNumber + 1;
552
553 if (_errMode == errModeBadSequence) {
554 outgoingSeqNumber++;
555 }
556
557 return outgoingSeqNumber;
558}
559
560QString MockLinkFTP::_createTestTempFile(int size)
561{
562 QTemporaryFile tmpFile(QDir::tempPath() + QStringLiteral("/MockLinkFTPTestCaseXXXXXX"));
563 tmpFile.setAutoRemove(false);
564
565 if (tmpFile.open()) {
566 for (int i = 0; i < size; i++) {
567 (void) tmpFile.write(QByteArray(1, static_cast<char>(i % 255)));
568 }
569 tmpFile.close();
570 }
571
572 return tmpFile.fileName();
573}
574
575QString MockLinkFTP::_generateParamPck(bool withDefaults)
576{
577 // AP_PARAM types used in the binary param.pck format
578 enum APParamType : quint8 {
579 AP_PARAM_INT8 = 1,
580 AP_PARAM_INT16 = 2,
581 AP_PARAM_INT32 = 3,
582 AP_PARAM_FLOAT = 4,
583 };
584
585 // ArduPilot binary param.pck format magic numbers.
586 // See AP_Filesystem_Param.cpp in ArduPilot source (AP_PARAM_HEADER_MAGIC / AP_PARAM_HEADER_MAGIC_DEFAULT).
587 constexpr quint16 magicStandard = 0x671B; // param.pck without defaults
588 constexpr quint16 magicWithDefaults = 0x671C; // param.pck?withdefaults=1
589 constexpr int readSize = 239; // Max data bytes per MAVLink FTP burst: MAVLink payload (251 bytes) minus FTP header (12 bytes) = 239.
590 // This matches the MAVLink FTP spec / PX4-ArduPilot implementations and is critical to correct chunking and padding.
591
592 // Get params for component 1 (MAV_COMP_ID_AUTOPILOT1)
593 constexpr int compId = 1;
594 const auto &valueMap = _mockLink->_mapParamName2Value;
595 const auto &typeMap = _mockLink->_mapParamName2MavParamType;
596 if (!valueMap.contains(compId) || !typeMap.contains(compId)) {
597 qCWarning(MockLinkFTPLog) << "_generateParamPck: no parameters for component" << compId;
598 return QString();
599 }
600
601 const auto &values = valueMap[compId];
602 const auto &types = typeMap[compId];
603
604 // Sort parameter names alphabetically (matching ArduPilot behavior)
605 QStringList paramNames = values.keys();
606 paramNames.sort();
607
608 const quint16 numParams = static_cast<quint16>(paramNames.size());
609
610 // Map MAV_PARAM_TYPE to AP_PARAM type and value size
611 auto mapType = [](MAV_PARAM_TYPE mavType, quint8 &apType, int &valueSize) {
612 switch (mavType) {
613 case MAV_PARAM_TYPE_UINT8:
614 case MAV_PARAM_TYPE_INT8:
615 apType = AP_PARAM_INT8;
616 valueSize = 1;
617 break;
618 case MAV_PARAM_TYPE_UINT16:
619 case MAV_PARAM_TYPE_INT16:
620 apType = AP_PARAM_INT16;
621 valueSize = 2;
622 break;
623 case MAV_PARAM_TYPE_UINT32:
624 case MAV_PARAM_TYPE_INT32:
625 apType = AP_PARAM_INT32;
626 valueSize = 4;
627 break;
628 case MAV_PARAM_TYPE_REAL32:
629 apType = AP_PARAM_FLOAT;
630 valueSize = 4;
631 break;
632 default:
633 apType = AP_PARAM_FLOAT;
634 valueSize = 4;
635 break;
636 }
637 };
638
639 QByteArray data;
640 QDataStream stream(&data, QIODevice::WriteOnly);
641 stream.setByteOrder(QDataStream::LittleEndian);
642
643 // Write header
644 const quint16 magic = withDefaults ? magicWithDefaults : magicStandard;
645 stream << magic << numParams << numParams;
646
647 QByteArray previousName;
648 constexpr int headerSize = 6; // 2 bytes magic + 2 bytes numParams + 2 bytes totalParams
649
650 for (const QString &name : paramNames) {
651 const QVariant &value = values[name];
652 const MAV_PARAM_TYPE mavType = types[name];
653 const QByteArray nameBytes = name.toLatin1();
654
655 quint8 apType = 0;
656 int valueSize = 0;
657 mapType(mavType, apType, valueSize);
658
659 // Compute common prefix with previous parameter name
660 const int previousNameLen = previousName.size();
661 const int currentNameLen = nameBytes.size();
662 int commonLen = 0;
663 // common_len is limited to 15 because common_len + name_len <= 16 and name_len must be >= 1
664 const int maxCommon = std::min({previousNameLen, currentNameLen, 15});
665 while (commonLen < maxCommon && nameBytes[commonLen] == previousName[commonLen]) {
666 commonLen++;
667 }
668
669 int nameLen = currentNameLen - commonLen;
670 // name_len is encoded as (name_len - 1) in 4 bits, so it must be >= 1.
671 // If the entire name matched the common prefix, steal one char back.
672 if (nameLen == 0 && commonLen > 0) {
673 nameLen = 1;
674 commonLen--;
675 }
676 // Ensure name_len + common_len <= 16
677 if (nameLen + commonLen > 16) {
678 commonLen = 16 - nameLen;
679 }
680 // name_len must fit in 4 bits as (name_len - 1)
681 if (nameLen > 16) {
682 nameLen = 16;
683 commonLen = 0;
684 }
685
686 // For MockLink all params are at defaults, so when withDefaults is requested
687 // we still include the default value for every param (matching real ArduPilot
688 // behavior where value == default means no default flag, but we include them
689 // so QGC can show default values in the UI)
690 const bool addDefault = withDefaults;
691 const quint8 flags = addDefault ? 0x01 : 0x00;
692 const int packedLen = 2 + nameLen + valueSize + (addDefault ? valueSize : 0);
693
694 // FTP reads data in fixed-size blocks (readSize = 239 bytes, the MAVLink FTP
695 // payload). If a multi-byte value straddles a block boundary, a retransmitted
696 // block could overwrite part of the value with stale data, corrupting it.
697 // To prevent this, ArduPilot inserts zero-byte padding before the entry so
698 // the value bytes land entirely within one block. The parser skips leading
699 // zeros between entries. See AP_Filesystem_Param::pack_param.
700 if (valueSize > 1) {
701 const quint32 dataOfs = static_cast<quint32>(data.size()) - headerSize;
702 const quint32 endOfs = dataOfs + static_cast<quint32>(packedLen);
703 const quint32 endMod = endOfs % readSize;
704 if (endMod > 0 && endMod < static_cast<quint32>(valueSize)) {
705 const int pad = valueSize - static_cast<int>(endMod);
706 for (int i = 0; i < pad; i++) {
707 stream << static_cast<quint8>(0);
708 }
709 }
710 }
711
712 // Type + flags byte
713 stream << static_cast<quint8>(apType | (flags << 4));
714 // Name encoding byte: upper 4 bits = (name_len - 1), lower 4 bits = common_len
715 stream << static_cast<quint8>(((nameLen - 1) << 4) | commonLen);
716 // Write the unique suffix of the name
717 stream.writeRawData(nameBytes.constData() + commonLen, nameLen);
718
719 // Write parameter value
720 switch (apType) {
721 case AP_PARAM_INT8: {
722 const qint8 v = static_cast<qint8>(value.toInt());
723 stream << v;
724 if (addDefault) stream << v;
725 break;
726 }
727 case AP_PARAM_INT16: {
728 const qint16 v = static_cast<qint16>(value.toInt());
729 stream << v;
730 if (addDefault) stream << v;
731 break;
732 }
733 case AP_PARAM_INT32: {
734 const qint32 v = value.toInt();
735 stream << v;
736 if (addDefault) stream << v;
737 break;
738 }
739 case AP_PARAM_FLOAT: {
740 const float f = value.toFloat();
741 qint32 raw;
742 memcpy(&raw, &f, sizeof(raw));
743 stream << raw;
744 if (addDefault) stream << raw;
745 break;
746 }
747 }
748
749 previousName = nameBytes;
750 }
751
752 // Clean up previous temp file
753 if (!_paramPckTempFile.isEmpty()) {
754 QFile::remove(_paramPckTempFile);
755 _paramPckTempFile.clear();
756 }
757
758 // Write to temp file
759 QTemporaryFile tmpFile(QDir::temp().filePath(QStringLiteral("MockLinkParamPckXXXXXX")));
760 tmpFile.setAutoRemove(false);
761
762 if (!tmpFile.open()) {
763 qCWarning(MockLinkFTPLog) << "_generateParamPck: failed to create temp file";
764 return QString();
765 }
766
767 tmpFile.write(data);
768 tmpFile.close();
769 _paramPckTempFile = tmpFile.fileName();
770
771 qCDebug(MockLinkFTPLog) << "_generateParamPck: generated" << numParams << "params,"
772 << data.size() << "bytes, withDefaults:" << withDefaults
773 << "file:" << tmpFile.fileName();
774
775 return tmpFile.fileName();
776}
Error error
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
uint8_t mavlinkChannel() const
ErrorCode_t
Error codes returned in Nak response PayloadHeader.data[0].
Definition MAVLinkFTP.h:61
@ kErrFail
Unknown failure.
Definition MAVLinkFTP.h:63
@ kErrEOF
Offset past end of file for List and Read commands.
Definition MAVLinkFTP.h:68
@ kErrUnknownCommand
Unknown command opcode.
Definition MAVLinkFTP.h:69
@ kErrFailErrno
errno sent back in PayloadHeader.data[1]
Definition MAVLinkFTP.h:64
@ kErrInvalidSession
Session is not currently open.
Definition MAVLinkFTP.h:66
@ kErrFailFileNotFound
Definition MAVLinkFTP.h:72
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
Definition MAVLinkFTP.h:46
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
Definition MAVLinkFTP.h:45
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
Definition MAVLinkFTP.h:43
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
Definition MAVLinkFTP.h:44
@ kCmdOpenFileWO
Opens file at <path> for writing, returns <session>
Definition MAVLinkFTP.h:50
@ kCmdResetSessions
Terminates all open Read sessions.
Definition MAVLinkFTP.h:41
@ kCmdNone
ignored, always acked
Definition MAVLinkFTP.h:39
@ kRspAck
Ack response.
Definition MAVLinkFTP.h:56
@ kCmdBurstReadFile
Burst download session file.
Definition MAVLinkFTP.h:54
@ kCmdTerminateSession
Terminates open Read session.
Definition MAVLinkFTP.h:40
@ kRspNak
Nak response.
Definition MAVLinkFTP.h:57
@ kCmdListDirectory
List files in <path> from <offset>
Definition MAVLinkFTP.h:42
Mock implementation of Mavlink FTP server.
Definition MockLinkFTP.h:16
void resetCommandReceived()
You can connect to this signal to be notified when the server receives a Reset command.
void terminateCommandReceived()
You can connect to this signal to be notified when the server receives a Terminate command.
static constexpr const char * sizeFilenamePrefix
Definition MockLinkFTP.h:69
void mavlinkMessageReceived(const mavlink_message_t &message)
Called to handle an FTP message.
@ errModeBadSequence
Return response with bad sequence number.
Definition MockLinkFTP.h:49
@ errModeNoSecondResponseAllowRetry
No response to subsequent request to initial command, error will be cleared after this so retry will ...
Definition MockLinkFTP.h:47
@ errModeNakSecondResponse
Nak subsequent request to initial command.
Definition MockLinkFTP.h:48
@ errModeNoResponse
No response to any request, client should eventually time out with no Ack.
Definition MockLinkFTP.h:44
@ errModeNone
No error, respond correctly.
Definition MockLinkFTP.h:43
@ errModeNoSecondResponse
No response to subsequent request to initial command.
Definition MockLinkFTP.h:46
@ errModeNakResponse
Nak all requests.
Definition MockLinkFTP.h:45