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/QDir>
6#include <QtCore/QTemporaryFile>
7
8QGC_LOGGING_CATEGORY(MockLinkFTPLog, "Comms.MockLink.MockLinkFTP")
9
10MockLinkFTP::MockLinkFTP(uint8_t systemIdServer, uint8_t componentIdServer, MockLink *mockLink)
11 : QObject(mockLink)
12 , _systemIdServer(systemIdServer)
13 , _componentIdServer(componentIdServer)
14 , _mockLink(mockLink)
15{
16 // qCDebug(MockLinkFTPLog) << Q_FUNC_INFO << this;
17}
18
20{
21 // qCDebug(MockLinkFTPLog) << Q_FUNC_INFO << this;
22}
23
24void MockLinkFTP::ensureNullTemination(MavlinkFTP::Request *request)
25{
26 if (request->hdr.size < sizeof(request->data)) {
27 request->data[request->hdr.size] = '\0';
28 } else {
29 request->data[sizeof(request->data) - 1] = '\0';
30 }
31}
32
33void MockLinkFTP::_listCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
34{
35 MavlinkFTP::Request ackResponse{};
36 ensureNullTemination(request);
37
38 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
39
40 // We only support root path
41 const QString path = reinterpret_cast<char*>(&request->data[0]);
42 if (!path.isEmpty() && path != "/") {
43 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
44 return;
45 }
46
47 if (request->hdr.offset > 0) {
48 if (_errMode == errModeNakSecondResponse) {
49 // Nak error all subsequent requests
50 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
51 return;
52 }
53
54 if (_errMode == errModeNoSecondResponse) {
55 // No response for all subsequent requests
56 return;
57 }
58
59 if (_errMode == errModeNoSecondResponseAllowRetry) {
60 // No response to this request, subsequent requests will succeed
61 _errMode = errModeNone;
62 return;
63 }
64 }
65
66 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
67 ackResponse.hdr.req_opcode = MavlinkFTP::kCmdListDirectory;
68 ackResponse.hdr.session = 0;
69 ackResponse.hdr.offset = request->hdr.offset;
70 ackResponse.hdr.size = 0;
71
72 // MockLink sends two directory entries per packet for a maximum of 3 packets, 6 total entries
73 if (request->hdr.offset <= 5) {
74 char *bufPtr = reinterpret_cast<char*>(&ackResponse.data[0]);
75 QString dirEntry = QStringLiteral("Ffile%1.txt").arg(request->hdr.offset);
76 auto cchDirEntry = dirEntry.length();
77 (void) strncpy(bufPtr, dirEntry.toStdString().c_str(), cchDirEntry);
78 ackResponse.hdr.size += dirEntry.length() + 1;
79 bufPtr += cchDirEntry + 1;
80 dirEntry = QStringLiteral("Ffile%1.txt").arg(request->hdr.offset + 1);
81 cchDirEntry = dirEntry.length();
82 (void) strncpy(bufPtr, dirEntry.toStdString().c_str(), cchDirEntry);
83 ackResponse.hdr.size += dirEntry.length() + 1;
84 } else {
85 ackResponse.hdr.opcode = MavlinkFTP::kRspNak;
86 ackResponse.data[0] = MavlinkFTP::kErrEOF;
87 ackResponse.hdr.size = 1;
88 }
89
90 _sendResponse(senderSystemId, senderComponentId, &ackResponse, outgoingSeqNumber);
91}
92
93void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
94{
95 MavlinkFTP::Request response{};
96 ensureNullTemination(request);
97 const QString path = reinterpret_cast<char*>(request->data);
98
99 _uploadSession.reset();
100
101 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
102
103 const size_t cchPath = strnlen(reinterpret_cast<char*>(request->data), sizeof(request->data));
104 Q_ASSERT(cchPath != sizeof(request->data));
105 Q_UNUSED(cchPath); // Fix initialized-but-not-referenced warning on release builds
106
107 _currentFile.close();
108
109 QString tmpFilename;
110 const QString sizePrefix = sizeFilenamePrefix;
111 if (path.startsWith(sizePrefix)) {
112 const QString sizeString = path.right(path.length() - sizePrefix.length());
113 tmpFilename = _createTestTempFile(sizeString.toInt());
114 } else if (path == "/general.json") {
115 tmpFilename = QStringLiteral(":MockLink/General.MetaData.json");
116 } else if (path == "/general.json.xz") {
117 tmpFilename = QStringLiteral(":MockLink/General.MetaData.json.xz");
118 } else if (path == "/parameter.json") {
119 tmpFilename = QStringLiteral(":MockLink/Parameter.MetaData.json");
120 } else if (path == "/parameter.json.xz") {
121 tmpFilename = QStringLiteral(":MockLink/Parameter.MetaData.json.xz");
122 } else if (_BinParamFileEnabled && (path == "@PARAM/param.pck")) {
123 tmpFilename = ":MockLink/Arduplane.params.ftp.bin";
124 }
125
126 if (!tmpFilename.isEmpty()) {
127 _currentFile.setFileName(tmpFilename);
128 if (!_currentFile.open(QIODevice::ReadOnly)) {
129 _sendNakErrno(senderSystemId, senderComponentId, _currentFile.error(), outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
130 return;
131 }
132 } else {
133 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFailFileNotFound, outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
134 return;
135 }
136
137 response.hdr.opcode = MavlinkFTP::kRspAck;
138 response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileRO;
139 response.hdr.session = _sessionId;
140
141 // Data contains file length
142 response.hdr.size = sizeof(uint32_t);
143
144 // Ardupilot sends constant wrong file size for parameter file due to dynamic on the fly generation
145 response.openFileLength = ((path == "@PARAM/param.pck") ? qPow(1024, 2) : _currentFile.size());
146
147 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
148}
149
150void MockLinkFTP::_createFileCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
151{
152 ensureNullTemination(request);
153
154 const QString path = reinterpret_cast<char*>(request->data);
155 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
156
157 if (path.isEmpty()) {
158 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdCreateFile);
159 return;
160 }
161
162 _uploadSession.reset();
163 _uploadSession.active = true;
164 _uploadSession.remotePath = path;
165
166 MavlinkFTP::Request response{};
167 response.hdr.opcode = MavlinkFTP::kRspAck;
168 response.hdr.req_opcode = MavlinkFTP::kCmdCreateFile;
169 response.hdr.session = _sessionId;
170 response.hdr.size = 0;
171
172 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
173}
174
175void MockLinkFTP::_openFileWOCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
176{
177 ensureNullTemination(request);
178
179 const QString path = reinterpret_cast<char*>(request->data);
180 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
181
182 if (path.isEmpty()) {
183 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdOpenFileWO);
184 return;
185 }
186
187 _uploadSession.reset();
188 _uploadSession.active = true;
189 _uploadSession.remotePath = path;
190
191 MavlinkFTP::Request response{};
192 response.hdr.opcode = MavlinkFTP::kRspAck;
193 response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileWO;
194 response.hdr.session = _sessionId;
195 response.hdr.size = 0;
196
197 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
198}
199
200void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
201{
202 MavlinkFTP::Request response{};
203 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
204
205 if (request->hdr.session != _sessionId) {
206 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
207 return;
208 }
209
210 const uint32_t readOffset = request->hdr.offset; // offset into file for reading
211 if (readOffset != 0) {
212 // If we get here it means the client is requesting additional data past the first request
213 if (_errMode == errModeNakSecondResponse) {
214 // Nak error all subsequent requests
215 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
216 return;
217 }
218
219 if (_errMode == errModeNoSecondResponse) {
220 // No rsponse for all subsequent requests
221 return;
222 }
223 }
224
225 if (readOffset >= _currentFile.size()) {
226 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
227 return;
228 }
229
230 const uint8_t cBytesToRead = static_cast<uint8_t>(qMin(static_cast<qint64>(sizeof(response.data)), _currentFile.size() - readOffset));
231 (void) _currentFile.seek(readOffset);
232 const QByteArray bytes = _currentFile.read(cBytesToRead);
233 (void) memcpy(response.data, bytes.constData(), cBytesToRead);
234
235 // We should always have written something, otherwise there is something wrong with the code above
236 Q_ASSERT(cBytesToRead);
237
238 response.hdr.session = _sessionId;
239 response.hdr.size = cBytesToRead;
240 response.hdr.offset = request->hdr.offset;
241 response.hdr.opcode = MavlinkFTP::kRspAck;
242 response.hdr.req_opcode = MavlinkFTP::kCmdReadFile;
243
244 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
245}
246
247void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
248{
249 MavlinkFTP::Request response{};
250 uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
251
252 if (request->hdr.session != _sessionId) {
253 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
254 return;
255 }
256
257 constexpr int burstMax = 10;
258 int burstCount = 1;
259 uint32_t burstOffset = request->hdr.offset;
260
261 while ((burstOffset < _currentFile.size()) && (burstCount++ < burstMax)) {
262 _currentFile.seek(burstOffset);
263
264 const uint8_t cBytes = static_cast<uint8_t>(qMin(static_cast<qint64>(sizeof(response.data)), _currentFile.size() - burstOffset));
265 const QByteArray bytes = _currentFile.read(cBytes);
266 Q_ASSERT(cBytes); // We should always have written something, otherwise there is something wrong with the code above
267
268 (void) memcpy(response.data, bytes.constData(), cBytes);
269
270 response.hdr.session = _sessionId;
271 response.hdr.size = cBytes;
272 response.hdr.offset = burstOffset;
273 response.hdr.opcode = MavlinkFTP::kRspAck;
274 response.hdr.req_opcode = MavlinkFTP::kCmdBurstReadFile;
275 response.hdr.burstComplete = (burstCount == burstMax) ? 1 : 0;
276
277 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
278
279 outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
280 burstOffset += cBytes;
281 }
282
283 if (burstOffset >= _currentFile.size()) {
284 // Burst is fully complete
285 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
286 }
287}
288
289void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
290{
291 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
292
293 if (request->hdr.session != _sessionId) {
294 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
295 return;
296 }
297
298 _currentFile.close();
299 _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
300
301 _finalizeActiveUpload();
302
304}
305
306void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber)
307{
308 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
309
310 _currentFile.close();
311 _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdResetSessions);
312
313 _finalizeActiveUpload();
314
316}
317
318void MockLinkFTP::_writeCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
319{
320 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
321
322 if ((request->hdr.session != _sessionId) || !_uploadSession.active) {
323 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
324 return;
325 }
326
327 if (request->hdr.offset > static_cast<uint32_t>(_uploadSession.buffer.size())) {
328 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
329 return;
330 }
331
332 if (request->hdr.offset != 0) {
333 if (_errMode == errModeNakSecondResponse) {
334 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
335 return;
336 }
337
338 if (_errMode == errModeNoSecondResponse) {
339 return;
340 }
341
342 if (_errMode == errModeNoSecondResponseAllowRetry) {
343 _errMode = errModeNone;
344 return;
345 }
346 }
347
348 const uint32_t bytesToWrite = request->hdr.size;
349 if (bytesToWrite > sizeof(request->data)) {
350 _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdWriteFile);
351 return;
352 }
353
354 const uint32_t requiredSize = request->hdr.offset + bytesToWrite;
355 if (requiredSize > static_cast<uint32_t>(_uploadSession.buffer.size())) {
356 _uploadSession.buffer.resize(requiredSize);
357 }
358
359 if (bytesToWrite > 0) {
360 (void) memcpy(_uploadSession.buffer.data() + request->hdr.offset, request->data, bytesToWrite);
361 }
362
363 MavlinkFTP::Request response{};
364 response.hdr.opcode = MavlinkFTP::kRspAck;
365 response.hdr.req_opcode = MavlinkFTP::kCmdWriteFile;
366 response.hdr.session = _sessionId;
367 response.hdr.size = 0;
368 response.hdr.offset = request->hdr.offset;
369
370 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
371}
372
373void MockLinkFTP::_finalizeActiveUpload()
374{
375 if (!_uploadSession.active) {
376 return;
377 }
378
379 if (!_uploadSession.remotePath.isEmpty()) {
380 _uploadedFiles.insert(_uploadSession.remotePath, _uploadSession.buffer);
381 }
382
383 _uploadSession.reset();
384}
385
387{
388 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
389 return;
390 }
391
392 mavlink_file_transfer_protocol_t requestFTP{};
393 mavlink_msg_file_transfer_protocol_decode(&message, &requestFTP);
394
395 if (requestFTP.target_system != _systemIdServer) {
396 return;
397 }
398
399 MavlinkFTP::Request *request = reinterpret_cast<MavlinkFTP::Request*>(&requestFTP.payload[0]);
400
401 // kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
402 if (_randomDropsEnabled && (request->hdr.opcode != MavlinkFTP::kCmdOpenFileRO) && (request->hdr.opcode != MavlinkFTP::kCmdResetSessions)) {
403 if ((rand() % 5) == 0) {
404 qCDebug(MockLinkFTPLog) << "MockLinkFTP: Random drop of incoming packet";
405 return;
406 }
407 }
408
409 if (_lastReplyValid && (request->hdr.seqNumber == (_lastReplySequence - 1))) {
410 // This is the same request as the one we replied to last. It means the (n)ack got lost, and the GCS
411 // resent the request
412 qCDebug(MockLinkFTPLog) << "MockLinkFTP: resending response";
413 _mockLink->respondWithMavlinkMessage(_lastReply);
414 return;
415 }
416
417 const uint16_t incomingSeqNumber = request->hdr.seqNumber;
418 const uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
419
420 if ((request->hdr.opcode != MavlinkFTP::kCmdResetSessions) && (request->hdr.opcode != MavlinkFTP::kCmdTerminateSession)) {
421 if (_errMode == errModeNoResponse) {
422 // Don't respond to any requests, this shold cause the client to eventually timeout waiting for the ack
423 return;
424 }
425
426 if (_errMode == errModeNakResponse) {
427 // Nak all requests, the actual error send back doesn't really matter as long as it's an error
428 _sendNak(message.sysid, message.compid, MavlinkFTP::kErrFail, outgoingSeqNumber, static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));
429 return;
430 }
431 }
432
433 MavlinkFTP::Request ackResponse{};
434 switch (request->hdr.opcode) {
436 // ignored, always acked
437 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
438 ackResponse.hdr.session = 0;
439 ackResponse.hdr.size = 0;
440 _sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
441 break;
443 _listCommand(message.sysid, message.compid, request, incomingSeqNumber);
444 break;
446 _openCommand(message.sysid, message.compid, request, incomingSeqNumber);
447 break;
449 _createFileCommand(message.sysid, message.compid, request, incomingSeqNumber);
450 break;
452 _openFileWOCommand(message.sysid, message.compid, request, incomingSeqNumber);
453 break;
455 _readCommand(message.sysid, message.compid, request, incomingSeqNumber);
456 break;
458 _burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
459 break;
461 _writeCommand(message.sysid, message.compid, request, incomingSeqNumber);
462 break;
464 _terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
465 break;
467 _resetCommand(message.sysid, message.compid, incomingSeqNumber);
468 break;
469 default:
470 // nack for all NYI opcodes
471 _sendNak(message.sysid, message.compid, MavlinkFTP::kErrUnknownCommand, outgoingSeqNumber, static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));
472 break;
473 }
474}
475
476void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
477{
478 MavlinkFTP::Request ackResponse{};
479
480 ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
481 ackResponse.hdr.req_opcode = reqOpcode;
482 ackResponse.hdr.session = _sessionId;
483 ackResponse.hdr.size = 0;
484
485 _sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
486}
487
488void MockLinkFTP::_sendNak(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::ErrorCode_t error, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
489{
490 MavlinkFTP::Request nakResponse{};
491
492 nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
493 nakResponse.hdr.req_opcode = reqOpcode;
494 nakResponse.hdr.session = _sessionId;
495 nakResponse.hdr.size = 1;
496 nakResponse.data[0] = error;
497
498 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
499}
500
501void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentId, uint8_t nakErrno, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
502{
503 MavlinkFTP::Request nakResponse{};
504
505 nakResponse.hdr.opcode = MavlinkFTP::kRspNak;
506 nakResponse.hdr.req_opcode = reqOpcode;
507 nakResponse.hdr.session = _sessionId;
508 nakResponse.hdr.size = 2;
509 nakResponse.data[0] = MavlinkFTP::kErrFailErrno;
510 nakResponse.data[1] = nakErrno;
511
512 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
513}
514
515
516void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
517{
518 request->hdr.seqNumber = seqNumber;
519 _lastReplySequence = seqNumber;
520 _lastReplyValid = true;
521
522 (void) mavlink_msg_file_transfer_protocol_pack_chan(
523 _systemIdServer, // System ID
524 _componentIdServer, // Component ID
525 _mockLink->mavlinkChannel(),
526 &_lastReply, // Mavlink Message to pack into
527 0, // Target network
528 targetSystemId,
529 targetComponentId,
530 reinterpret_cast<uint8_t*>(request) // Payload
531 );
532
533 // kCmdOpenFileRO and kCmdResetSessions don't support retry so we can't drop those
534 if (_randomDropsEnabled && (request->hdr.req_opcode != MavlinkFTP::kCmdOpenFileRO) && (request->hdr.req_opcode != MavlinkFTP::kCmdResetSessions)) {
535 if ((rand() % 5) == 0) {
536 qCDebug(MockLinkFTPLog) << "MockLinkFTP: Random drop of outgoing packet";
537 return;
538 }
539 }
540
541 _mockLink->respondWithMavlinkMessage(_lastReply);
542}
543
544
545uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber) const
546{
547 uint16_t outgoingSeqNumber = seqNumber + 1;
548
549 if (_errMode == errModeBadSequence) {
550 outgoingSeqNumber++;
551 }
552
553 return outgoingSeqNumber;
554}
555
556QString MockLinkFTP::_createTestTempFile(int size)
557{
558 QTemporaryFile tmpFile(QDir::tempPath() + QStringLiteral("/MockLinkFTPTestCaseXXXXXX"));
559 tmpFile.setAutoRemove(false);
560
561 if (tmpFile.open()) {
562 for (int i = 0; i < size; i++) {
563 (void) tmpFile.write(QByteArray(1, static_cast<char>(i % 255)));
564 }
565 tmpFile.close();
566 }
567
568 return tmpFile.fileName();
569}
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:65
@ kErrFail
Unknown failure.
Definition MAVLinkFTP.h:67
@ kErrEOF
Offset past end of file for List and Read commands.
Definition MAVLinkFTP.h:72
@ kErrUnknownCommand
Unknown command opcode.
Definition MAVLinkFTP.h:73
@ kErrFailErrno
errno sent back in PayloadHeader.data[1]
Definition MAVLinkFTP.h:68
@ kErrInvalidSession
Session is not currently open.
Definition MAVLinkFTP.h:70
@ kErrFailFileNotFound
Definition MAVLinkFTP.h:76
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
Definition MAVLinkFTP.h:50
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
Definition MAVLinkFTP.h:49
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
Definition MAVLinkFTP.h:47
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
Definition MAVLinkFTP.h:48
@ kCmdOpenFileWO
Opens file at <path> for writing, returns <session>
Definition MAVLinkFTP.h:54
@ kCmdResetSessions
Terminates all open Read sessions.
Definition MAVLinkFTP.h:45
@ kCmdNone
ignored, always acked
Definition MAVLinkFTP.h:43
@ kRspAck
Ack response.
Definition MAVLinkFTP.h:60
@ kCmdBurstReadFile
Burst download session file.
Definition MAVLinkFTP.h:58
@ kCmdTerminateSession
Terminates open Read session.
Definition MAVLinkFTP.h:44
@ kRspNak
Nak response.
Definition MAVLinkFTP.h:61
@ kCmdListDirectory
List files in <path> from <offset>
Definition MAVLinkFTP.h:46
Mock implementation of Mavlink FTP server.
Definition MockLinkFTP.h:18
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:72
void mavlinkMessageReceived(const mavlink_message_t &message)
Called to handle an FTP message.
@ errModeBadSequence
Return response with bad sequence number.
Definition MockLinkFTP.h:52
@ errModeNoSecondResponseAllowRetry
No response to subsequent request to initial command, error will be cleared after this so retry will ...
Definition MockLinkFTP.h:50
@ errModeNakSecondResponse
Nak subsequent request to initial command.
Definition MockLinkFTP.h:51
@ errModeNoResponse
No response to any request, client should eventually time out with no Ack.
Definition MockLinkFTP.h:47
@ errModeNone
No error, respond correctly.
Definition MockLinkFTP.h:46
@ errModeNoSecondResponse
No response to subsequent request to initial command.
Definition MockLinkFTP.h:49
@ errModeNakResponse
Nak all requests.
Definition MockLinkFTP.h:48