5#include <QtCore/QDataStream>
7#include <QtCore/QTemporaryFile>
13 , _systemIdServer(systemIdServer)
14 , _componentIdServer(componentIdServer)
22 if (!_paramPckTempFile.isEmpty()) {
23 QFile::remove(_paramPckTempFile);
27void MockLinkFTP::ensureNullTemination(MavlinkFTP::Request *request)
29 if (request->hdr.size <
sizeof(request->data)) {
30 request->data[request->hdr.size] =
'\0';
32 request->data[
sizeof(request->data) - 1] =
'\0';
36void MockLinkFTP::_listCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
38 MavlinkFTP::Request ackResponse{};
39 ensureNullTemination(request);
41 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
44 const QString path =
reinterpret_cast<char*
>(&request->data[0]);
45 if (!path.isEmpty() && path !=
"/") {
50 if (request->hdr.offset > 0) {
71 ackResponse.hdr.session = 0;
72 ackResponse.hdr.offset = request->hdr.offset;
73 ackResponse.hdr.size = 0;
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;
90 ackResponse.hdr.size = 1;
93 _sendResponse(senderSystemId, senderComponentId, &ackResponse, outgoingSeqNumber);
96void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
98 MavlinkFTP::Request response{};
99 ensureNullTemination(request);
100 const QString path =
reinterpret_cast<char*
>(request->data);
102 _uploadSession.reset();
104 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
106 const size_t cchPath = strnlen(
reinterpret_cast<char*
>(request->data),
sizeof(request->data));
107 Q_ASSERT(cchPath !=
sizeof(request->data));
110 _currentFile.close();
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);
130 if (!tmpFilename.isEmpty()) {
131 _currentFile.setFileName(tmpFilename);
132 if (!_currentFile.open(QIODevice::ReadOnly)) {
143 response.hdr.session = _sessionId;
146 response.hdr.size =
sizeof(uint32_t);
149 response.openFileLength = ((path ==
"@PARAM/param.pck" || path.startsWith(
"@PARAM/param.pck?")) ? qPow(1024, 2) : _currentFile.size());
151 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
154void MockLinkFTP::_createFileCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
156 ensureNullTemination(request);
158 const QString path =
reinterpret_cast<char*
>(request->data);
159 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
161 if (path.isEmpty()) {
166 _uploadSession.reset();
167 _uploadSession.active =
true;
168 _uploadSession.remotePath = path;
170 MavlinkFTP::Request response{};
173 response.hdr.session = _sessionId;
174 response.hdr.size = 0;
176 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
179void MockLinkFTP::_openFileWOCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
181 ensureNullTemination(request);
183 const QString path =
reinterpret_cast<char*
>(request->data);
184 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
186 if (path.isEmpty()) {
191 _uploadSession.reset();
192 _uploadSession.active =
true;
193 _uploadSession.remotePath = path;
195 MavlinkFTP::Request response{};
198 response.hdr.session = _sessionId;
199 response.hdr.size = 0;
201 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
204void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
206 MavlinkFTP::Request response{};
207 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
209 if (request->hdr.session != _sessionId) {
214 const uint32_t readOffset = request->hdr.offset;
215 if (readOffset != 0) {
229 if (readOffset >= _currentFile.size()) {
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);
240 Q_ASSERT(cBytesToRead);
242 response.hdr.session = _sessionId;
243 response.hdr.size = cBytesToRead;
244 response.hdr.offset = request->hdr.offset;
248 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
251void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
253 MavlinkFTP::Request response{};
254 uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
256 if (request->hdr.session != _sessionId) {
261 constexpr int burstMax = 10;
263 uint32_t burstOffset = request->hdr.offset;
265 while ((burstOffset < _currentFile.size()) && (burstCount++ < burstMax)) {
266 _currentFile.seek(burstOffset);
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);
272 (void) memcpy(response.data, bytes.constData(), cBytes);
274 response.hdr.session = _sessionId;
275 response.hdr.size = cBytes;
276 response.hdr.offset = burstOffset;
279 response.hdr.burstComplete = (burstCount == burstMax) ? 1 : 0;
281 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
283 outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
284 burstOffset += cBytes;
287 if (burstOffset >= _currentFile.size()) {
293void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
295 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
297 if (request->hdr.session != _sessionId) {
302 _currentFile.close();
305 _finalizeActiveUpload();
310void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber)
312 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
314 _currentFile.close();
317 _finalizeActiveUpload();
322void MockLinkFTP::_writeCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
324 const uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
326 if ((request->hdr.session != _sessionId) || !_uploadSession.active) {
331 if (request->hdr.offset >
static_cast<uint32_t
>(_uploadSession.buffer.size())) {
336 if (request->hdr.offset != 0) {
352 const uint32_t bytesToWrite = request->hdr.size;
353 if (bytesToWrite >
sizeof(request->data)) {
358 const uint32_t requiredSize = request->hdr.offset + bytesToWrite;
359 if (requiredSize >
static_cast<uint32_t
>(_uploadSession.buffer.size())) {
360 _uploadSession.buffer.resize(requiredSize);
363 if (bytesToWrite > 0) {
364 (void) memcpy(_uploadSession.buffer.data() + request->hdr.offset, request->data, bytesToWrite);
367 MavlinkFTP::Request response{};
370 response.hdr.session = _sessionId;
371 response.hdr.size = 0;
372 response.hdr.offset = request->hdr.offset;
374 _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
377void MockLinkFTP::_finalizeActiveUpload()
379 if (!_uploadSession.active) {
383 if (!_uploadSession.remotePath.isEmpty()) {
384 _uploadedFiles.insert(_uploadSession.remotePath, _uploadSession.buffer);
387 _uploadSession.reset();
392 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
396 mavlink_file_transfer_protocol_t requestFTP{};
397 mavlink_msg_file_transfer_protocol_decode(&message, &requestFTP);
399 if (requestFTP.target_system != _systemIdServer) {
403 MavlinkFTP::Request *request =
reinterpret_cast<MavlinkFTP::Request*
>(&requestFTP.payload[0]);
407 if ((rand() % 5) == 0) {
408 qCDebug(MockLinkFTPLog) <<
"MockLinkFTP: Random drop of incoming packet";
413 if (_lastReplyValid && (request->hdr.seqNumber == (_lastReplySequence - 1))) {
416 qCDebug(MockLinkFTPLog) <<
"MockLinkFTP: resending response";
421 const uint16_t incomingSeqNumber = request->hdr.seqNumber;
422 const uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
437 MavlinkFTP::Request ackResponse{};
438 switch (request->hdr.opcode) {
442 ackResponse.hdr.session = 0;
443 ackResponse.hdr.size = 0;
444 _sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
447 _listCommand(message.sysid, message.compid, request, incomingSeqNumber);
450 _openCommand(message.sysid, message.compid, request, incomingSeqNumber);
453 _createFileCommand(message.sysid, message.compid, request, incomingSeqNumber);
456 _openFileWOCommand(message.sysid, message.compid, request, incomingSeqNumber);
459 _readCommand(message.sysid, message.compid, request, incomingSeqNumber);
462 _burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
465 _writeCommand(message.sysid, message.compid, request, incomingSeqNumber);
468 _terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
471 _resetCommand(message.sysid, message.compid, incomingSeqNumber);
480void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, uint16_t seqNumber,
MavlinkFTP::OpCode_t reqOpcode)
482 MavlinkFTP::Request ackResponse{};
485 ackResponse.hdr.req_opcode = reqOpcode;
486 ackResponse.hdr.session = _sessionId;
487 ackResponse.hdr.size = 0;
489 _sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
494 MavlinkFTP::Request nakResponse{};
497 nakResponse.hdr.req_opcode = reqOpcode;
498 nakResponse.hdr.session = _sessionId;
499 nakResponse.hdr.size = 1;
500 nakResponse.data[0] =
error;
502 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
505void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentId, uint8_t nakErrno, uint16_t seqNumber,
MavlinkFTP::OpCode_t reqOpcode)
507 MavlinkFTP::Request nakResponse{};
510 nakResponse.hdr.req_opcode = reqOpcode;
511 nakResponse.hdr.session = _sessionId;
512 nakResponse.hdr.size = 2;
514 nakResponse.data[1] = nakErrno;
516 _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
520void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::Request *request, uint16_t seqNumber)
522 request->hdr.seqNumber = seqNumber;
523 _lastReplySequence = seqNumber;
524 _lastReplyValid =
true;
526 (void) mavlink_msg_file_transfer_protocol_pack_chan(
534 reinterpret_cast<uint8_t*
>(request)
539 if ((rand() % 5) == 0) {
540 qCDebug(MockLinkFTPLog) <<
"MockLinkFTP: Random drop of outgoing packet";
549uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber)
const
551 uint16_t outgoingSeqNumber = seqNumber + 1;
557 return outgoingSeqNumber;
560QString MockLinkFTP::_createTestTempFile(
int size)
562 QTemporaryFile tmpFile(QDir::tempPath() + QStringLiteral(
"/MockLinkFTPTestCaseXXXXXX"));
563 tmpFile.setAutoRemove(
false);
565 if (tmpFile.open()) {
566 for (
int i = 0; i < size; i++) {
567 (void) tmpFile.write(QByteArray(1,
static_cast<char>(i % 255)));
572 return tmpFile.fileName();
575QString MockLinkFTP::_generateParamPck(
bool withDefaults)
578 enum APParamType : quint8 {
587 constexpr quint16 magicStandard = 0x671B;
588 constexpr quint16 magicWithDefaults = 0x671C;
589 constexpr int readSize = 239;
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;
601 const auto &values = valueMap[compId];
602 const auto &types = typeMap[compId];
605 QStringList paramNames = values.keys();
608 const quint16 numParams =
static_cast<quint16
>(paramNames.size());
611 auto mapType = [](MAV_PARAM_TYPE mavType, quint8 &apType,
int &valueSize) {
613 case MAV_PARAM_TYPE_UINT8:
614 case MAV_PARAM_TYPE_INT8:
615 apType = AP_PARAM_INT8;
618 case MAV_PARAM_TYPE_UINT16:
619 case MAV_PARAM_TYPE_INT16:
620 apType = AP_PARAM_INT16;
623 case MAV_PARAM_TYPE_UINT32:
624 case MAV_PARAM_TYPE_INT32:
625 apType = AP_PARAM_INT32;
628 case MAV_PARAM_TYPE_REAL32:
629 apType = AP_PARAM_FLOAT;
633 apType = AP_PARAM_FLOAT;
640 QDataStream stream(&data, QIODevice::WriteOnly);
641 stream.setByteOrder(QDataStream::LittleEndian);
644 const quint16 magic = withDefaults ? magicWithDefaults : magicStandard;
645 stream << magic << numParams << numParams;
647 QByteArray previousName;
648 constexpr int headerSize = 6;
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();
657 mapType(mavType, apType, valueSize);
660 const int previousNameLen = previousName.size();
661 const int currentNameLen = nameBytes.size();
664 const int maxCommon = std::min({previousNameLen, currentNameLen, 15});
665 while (commonLen < maxCommon && nameBytes[commonLen] == previousName[commonLen]) {
669 int nameLen = currentNameLen - commonLen;
672 if (nameLen == 0 && commonLen > 0) {
677 if (nameLen + commonLen > 16) {
678 commonLen = 16 - nameLen;
690 const bool addDefault = withDefaults;
691 const quint8 flags = addDefault ? 0x01 : 0x00;
692 const int packedLen = 2 + nameLen + valueSize + (addDefault ? valueSize : 0);
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);
713 stream << static_cast<quint8>(apType | (flags << 4));
715 stream << static_cast<quint8>(((nameLen - 1) << 4) | commonLen);
717 stream.writeRawData(nameBytes.constData() + commonLen, nameLen);
721 case AP_PARAM_INT8: {
722 const qint8 v =
static_cast<qint8
>(value.toInt());
724 if (addDefault) stream << v;
727 case AP_PARAM_INT16: {
728 const qint16 v =
static_cast<qint16
>(value.toInt());
730 if (addDefault) stream << v;
733 case AP_PARAM_INT32: {
734 const qint32 v = value.toInt();
736 if (addDefault) stream << v;
739 case AP_PARAM_FLOAT: {
740 const float f = value.toFloat();
742 memcpy(&raw, &f,
sizeof(raw));
744 if (addDefault) stream << raw;
749 previousName = nameBytes;
753 if (!_paramPckTempFile.isEmpty()) {
754 QFile::remove(_paramPckTempFile);
755 _paramPckTempFile.clear();
759 QTemporaryFile tmpFile(QDir::temp().filePath(QStringLiteral(
"MockLinkParamPckXXXXXX")));
760 tmpFile.setAutoRemove(
false);
762 if (!tmpFile.open()) {
763 qCWarning(MockLinkFTPLog) <<
"_generateParamPck: failed to create temp file";
769 _paramPckTempFile = tmpFile.fileName();
771 qCDebug(MockLinkFTPLog) <<
"_generateParamPck: generated" << numParams <<
"params,"
772 << data.size() <<
"bytes, withDefaults:" << withDefaults
773 <<
"file:" << tmpFile.fileName();
775 return tmpFile.fileName();
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].
@ kErrFail
Unknown failure.
@ kErrEOF
Offset past end of file for List and Read commands.
@ kErrUnknownCommand
Unknown command opcode.
@ kErrFailErrno
errno sent back in PayloadHeader.data[1]
@ kErrInvalidSession
Session is not currently open.
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
@ kCmdOpenFileWO
Opens file at <path> for writing, returns <session>
@ kCmdResetSessions
Terminates all open Read sessions.
@ kCmdNone
ignored, always acked
@ kCmdBurstReadFile
Burst download session file.
@ kCmdTerminateSession
Terminates open Read session.
@ kCmdListDirectory
List files in <path> from <offset>
Mock implementation of Mavlink FTP server.
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
void mavlinkMessageReceived(const mavlink_message_t &message)
Called to handle an FTP message.
@ errModeBadSequence
Return response with bad sequence number.
@ errModeNoSecondResponseAllowRetry
No response to subsequent request to initial command, error will be cleared after this so retry will ...
@ errModeNakSecondResponse
Nak subsequent request to initial command.
@ errModeNoResponse
No response to any request, client should eventually time out with no Ack.
@ errModeNone
No error, respond correctly.
@ errModeNoSecondResponse
No response to subsequent request to initial command.
@ errModeNakResponse
Nak all requests.
void respondWithMavlinkMessage(const mavlink_message_t &msg)
Sends the specified mavlink message to QGC.