MockLinkFTP.cc 16.5 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10

11
#include "MockLinkFTP.h"
12 13
#include "MockLink.h"

14 15 16 17 18 19
const MockLinkFTP::ErrorMode_t MockLinkFTP::rgFailureModes[] = {
    MockLinkFTP::errModeNoResponse,
    MockLinkFTP::errModeNakResponse,
    MockLinkFTP::errModeNoSecondResponse,
    MockLinkFTP::errModeNakSecondResponse,
    MockLinkFTP::errModeBadSequence,
20
};
21
const size_t MockLinkFTP::cFailureModes = sizeof(MockLinkFTP::rgFailureModes) / sizeof(MockLinkFTP::rgFailureModes[0]);
22

23
const char* MockLinkFTP::sizeFilenamePrefix = "mocklink-size-";
24

25 26 27 28
MockLinkFTP::MockLinkFTP(uint8_t systemIdServer, uint8_t componentIdServer, MockLink* mockLink)
    : _systemIdServer   (systemIdServer)
    , _componentIdServer(componentIdServer)
    , _mockLink         (mockLink)
29
{
30 31 32
    srand(0); // make sure unit tests are deterministic
}

33
void MockLinkFTP::ensureNullTemination(MavlinkFTP::Request* request)
34 35 36
{
    if (request->hdr.size < sizeof(request->data)) {
        request->data[request->hdr.size] = '\0';
37

38 39 40
    } else {
        request->data[sizeof(request->data)-1] = '\0';
    }
41 42
}

43 44
/// @brief Handles List command requests. Only supports root folder paths.
///         File list returned is set using the setFileList method.
45
void MockLinkFTP::_listCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
46
{
47 48
    // FIXME: Does not support directories that span multiple packets
    
49
    MavlinkFTP::Request  ackResponse;
Don Gagne's avatar
Don Gagne committed
50
    QString                     path;
51
    uint16_t                    outgoingSeqNumber = _nextSeqNumber(seqNumber);
Don Gagne's avatar
Don Gagne committed
52

53 54
    ensureNullTemination(request);

55 56 57
    // We only support root path
    path = (char *)&request->data[0];
    if (!path.isEmpty() && path != "/") {
58
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
59 60 61 62 63
        return;
    }
    
    // Offset requested is past the end of the list
    if (request->hdr.offset > (uint32_t)_fileList.size()) {
64
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
65 66 67
        return;
    }
    
68 69
    ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
    ackResponse.hdr.req_opcode = MavlinkFTP::kCmdListDirectory;
70
    ackResponse.hdr.session = 0;
71
    ackResponse.hdr.offset = request->hdr.offset;
72
    ackResponse.hdr.size = 0;
73

74 75 76 77 78
    if (request->hdr.offset == 0) {
        // Requesting first batch of file names
        Q_ASSERT(_fileList.size());
        char *bufPtr = (char *)&ackResponse.data[0];
        for (int i=0; i<_fileList.size(); i++) {
79
            strcpy(bufPtr, _fileList[i].toStdString().c_str());
Don Gagne's avatar
Don Gagne committed
80 81
            uint8_t cchFilename = static_cast<uint8_t>(strlen(bufPtr));
            Q_ASSERT(cchFilename);
82 83 84
            ackResponse.hdr.size += cchFilename + 1;
            bufPtr += cchFilename + 1;
        }
85

86
        _sendResponse(senderSystemId, senderComponentId, &ackResponse, outgoingSeqNumber);
87 88
    } else if (_errMode == errModeNakSecondResponse) {
        // Nak error all subsequent requests
89
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
90 91 92 93
        return;
    } else if (_errMode == errModeNoSecondResponse) {
        // No response for all subsequent requests
        return;
94
    } else {
95
        // FIXME: Does not support directories that span multiple packets
96
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdListDirectory);
97 98 99
    }
}

100
void MockLinkFTP::_openCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
101
{
102 103 104 105
    MavlinkFTP::Request response;
    QString             path;
    uint16_t            outgoingSeqNumber = _nextSeqNumber(seqNumber);
    QString             tmpFilename;
106
    
107 108
    ensureNullTemination(request);

109 110
    size_t cchPath = strnlen((char *)request->data, sizeof(request->data));
    Q_ASSERT(cchPath != sizeof(request->data));
111
    Q_UNUSED(cchPath); // Fix initialized-but-not-referenced warning on release builds
112
    path = (char *)request->data;
113 114

    _currentFile.close();
115

116 117 118 119 120 121
    QString sizePrefix = sizeFilenamePrefix;
    if (path.startsWith(sizePrefix)) {
        QString sizeString = path.right(path.length() - sizePrefix.length());
        tmpFilename = _createTestTempFile(sizeString.toInt());
    } else if (path == "/version.json") {
        tmpFilename = ":MockLink/Version.MetaData.json";
122 123
    }

124 125 126 127 128 129 130 131
    if (!tmpFilename.isEmpty()) {
        _currentFile.setFileName(tmpFilename);
        if (!_currentFile.open(QIODevice::ReadOnly)) {
            _sendNakErrno(senderSystemId, senderComponentId, _currentFile.error(), outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
            return;
        }
    } else {
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFailFileNotFound, outgoingSeqNumber, MavlinkFTP::kCmdOpenFileRO);
132 133 134
        return;
    }
    
135 136 137
    response.hdr.opcode     = MavlinkFTP::kRspAck;
    response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileRO;
    response.hdr.session    = _sessionId;
138
    
139 140
    // Data contains file length
    response.hdr.size = sizeof(uint32_t);
141
    response.openFileLength = _currentFile.size();
142
    
143
    _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
144 145
}

146
void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
147
{
148 149
    MavlinkFTP::Request	response;
    uint16_t			outgoingSeqNumber = _nextSeqNumber(seqNumber);
150 151

    if (request->hdr.session != _sessionId) {
152
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
153 154 155
        return;
    }
    
156
    uint32_t readOffset = request->hdr.offset;  // offset into file for reading
157

158 159 160 161
    if (readOffset != 0) {
        // If we get here it means the client is requesting additional data past the first request
        if (_errMode == errModeNakSecondResponse) {
            // Nak error all subsequent requests
162
            _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
163 164 165 166 167 168 169
            return;
        } else if (_errMode == errModeNoSecondResponse) {
            // No rsponse for all subsequent requests
            return;
        }
    }
    
170 171
    if (readOffset >= _currentFile.size()) {
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
172 173 174
        return;
    }
    
175 176 177 178
    uint8_t cBytesToRead = (uint8_t)qMin((qint64)sizeof(response.data), _currentFile.size() - readOffset);
    _currentFile.seek(readOffset);
    QByteArray bytes = _currentFile.read(cBytesToRead);
    memcpy(response.data, bytes.constData(), cBytesToRead);
179
    
180
    // We should always have written something, otherwise there is something wrong with the code above
181
    Q_ASSERT(cBytesToRead);
182
    
183 184 185 186 187
    response.hdr.session    = _sessionId;
    response.hdr.size       = cBytesToRead;
    response.hdr.offset     = request->hdr.offset;
    response.hdr.opcode     = MavlinkFTP::kRspAck;
    response.hdr.req_opcode = MavlinkFTP::kCmdReadFile;
188

189
    _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
190 191
}

192
void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
193
{
194 195
    uint16_t            outgoingSeqNumber = _nextSeqNumber(seqNumber);
    MavlinkFTP::Request response;
196 197

    if (request->hdr.session != _sessionId) {
198
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
199 200 201
        return;
    }
    
202 203 204
    int         burstMax    = 10;
    int         burstCount  = 1;
    uint32_t    burstOffset = request->hdr.offset;
205
    
206 207 208 209 210
    while (burstOffset < _currentFile.size() && burstCount++ < burstMax) {
        _currentFile.seek(burstOffset);

        uint8_t     cBytes  = (uint8_t)qMin((qint64)sizeof(response.data), _currentFile.size() - burstOffset);
        QByteArray  bytes   = _currentFile.read(cBytes);
211

212
        // We should always have written something, otherwise there is something wrong with the code above
213 214 215 216 217 218 219 220 221 222 223
        Q_ASSERT(cBytes);

        memcpy(response.data, bytes.constData(), cBytes);

        response.hdr.session        = _sessionId;
        response.hdr.size           = cBytes;
        response.hdr.offset         = burstOffset;
        response.hdr.opcode         = MavlinkFTP::kRspAck;
        response.hdr.req_opcode     = MavlinkFTP::kCmdBurstReadFile;
        response.hdr.burstComplete  = burstCount == burstMax ? 1 : 0;

224
        _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
225 226
        
        outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
227
        burstOffset += cBytes;
228
    }
229

230
    _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
231 232
}

233
void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
234
{
235 236
    uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);

237
    if (request->hdr.session != _sessionId) {
238
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
239 240 241
        return;
    }
    
242
    _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
243

244 245 246
    emit terminateCommandReceived();
}

247
void MockLinkFTP::_resetCommand(uint8_t senderSystemId, uint8_t senderComponentId, uint16_t seqNumber)
248
{
249 250
    uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);
    
251 252
    _currentFile.close();
    _currentFile.remove();
253
    _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdResetSessions);
254 255 256
    
    emit resetCommandReceived();
}
257

258
void MockLinkFTP::mavlinkMessageReceived(const mavlink_message_t& message)
259 260 261 262
{
    if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
        return;
    }
263
    
264
    MavlinkFTP::Request  ackResponse;
265

266 267 268 269 270 271
    mavlink_file_transfer_protocol_t requestFTP;
    mavlink_msg_file_transfer_protocol_decode(&message, &requestFTP);
    
    if (requestFTP.target_system != _systemIdServer) {
        return;
    }
272

273
    MavlinkFTP::Request* request = (MavlinkFTP::Request*)&requestFTP.payload[0];
274

275 276 277 278 279 280 281 282 283 284 285 286 287 288
    if (_randomDropsEnabled) {
        if ((rand() % 5) == 0) {
            qDebug() << "MockLinkFTP: Random drop of incoming packet";
            return;
        }
    }

    if (_lastReplyValid && request->hdr.seqNumber == _lastReplySequence - 1) {
        // This is the same request as the one we replied to last. It means the (n)ack got lost, and the GCS
        // resent the request
        qDebug() << "MockLinkFTP: resending response";
        _mockLink->respondWithMavlinkMessage(_lastReply);
        return;
    }
289

290
    uint16_t incomingSeqNumber = request->hdr.seqNumber;
291 292
    uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
    
293
    if (request->hdr.opcode != MavlinkFTP::kCmdResetSessions && request->hdr.opcode != MavlinkFTP::kCmdTerminateSession) {
294 295 296 297 298
        if (_errMode == errModeNoResponse) {
            // Don't respond to any requests, this shold cause the client to eventually timeout waiting for the ack
            return;
        } else if (_errMode == errModeNakResponse) {
            // Nak all requests, the actual error send back doesn't really matter as long as it's an error
299
            _sendNak(message.sysid, message.compid, MavlinkFTP::kErrFail, outgoingSeqNumber, (MavlinkFTP::OpCode_t)request->hdr.opcode);
300 301
            return;
        }
302
    }
303

Don Gagne's avatar
Don Gagne committed
304
    switch (request->hdr.opcode) {
305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340
    case MavlinkFTP::kCmdNone:
        // ignored, always acked
        ackResponse.hdr.opcode = MavlinkFTP::kRspAck;
        ackResponse.hdr.session = 0;
        ackResponse.hdr.size = 0;
        _sendResponse(message.sysid, message.compid, &ackResponse, outgoingSeqNumber);
        break;

    case MavlinkFTP::kCmdListDirectory:
        _listCommand(message.sysid, message.compid, request, incomingSeqNumber);
        break;

    case MavlinkFTP::kCmdOpenFileRO:
        _openCommand(message.sysid, message.compid, request, incomingSeqNumber);
        break;

    case MavlinkFTP::kCmdReadFile:
        _readCommand(message.sysid, message.compid, request, incomingSeqNumber);
        break;

    case MavlinkFTP::kCmdBurstReadFile:
        _burstReadCommand(message.sysid, message.compid, request, incomingSeqNumber);
        break;

    case MavlinkFTP::kCmdTerminateSession:
        _terminateCommand(message.sysid, message.compid, request, incomingSeqNumber);
        break;

    case MavlinkFTP::kCmdResetSessions:
        _resetCommand(message.sysid, message.compid, incomingSeqNumber);
        break;

    default:
        // nack for all NYI opcodes
        _sendNak(message.sysid, message.compid, MavlinkFTP::kErrUnknownCommand, outgoingSeqNumber, (MavlinkFTP::OpCode_t)request->hdr.opcode);
        break;
341 342
    }
}
Don Gagne's avatar
Don Gagne committed
343

344
/// @brief Sends an Ack
345
void MockLinkFTP::_sendAck(uint8_t targetSystemId, uint8_t targetComponentId, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
346
{
347
    MavlinkFTP::Request ackResponse;
348
    
349 350 351 352
    ackResponse.hdr.opcode      = MavlinkFTP::kRspAck;
    ackResponse.hdr.req_opcode  = reqOpcode;
    ackResponse.hdr.session     = 0;
    ackResponse.hdr.size        = 0;
353
    
354
    _sendResponse(targetSystemId, targetComponentId, &ackResponse, seqNumber);
355 356
}

357
void MockLinkFTP::_sendNak(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::ErrorCode_t error, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
Don Gagne's avatar
Don Gagne committed
358
{
359
    MavlinkFTP::Request nakResponse;
Don Gagne's avatar
Don Gagne committed
360

361 362 363 364 365
    nakResponse.hdr.opcode      = MavlinkFTP::kRspNak;
    nakResponse.hdr.req_opcode  = reqOpcode;
    nakResponse.hdr.session     = 0;
    nakResponse.hdr.size        = 1;
    nakResponse.data[0]         = error;
Don Gagne's avatar
Don Gagne committed
366
    
367
    _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
Don Gagne's avatar
Don Gagne committed
368 369
}

370 371 372 373 374 375 376 377 378 379 380 381 382 383
void MockLinkFTP::_sendNakErrno(uint8_t targetSystemId, uint8_t targetComponentId, uint8_t nakErrno, uint16_t seqNumber, MavlinkFTP::OpCode_t reqOpcode)
{
    MavlinkFTP::Request nakResponse;

    nakResponse.hdr.opcode      = MavlinkFTP::kRspNak;
    nakResponse.hdr.req_opcode  = reqOpcode;
    nakResponse.hdr.session     = 0;
    nakResponse.hdr.size        = 2;
    nakResponse.data[0]         = MavlinkFTP::kErrFailErrno;
    nakResponse.data[1]         = nakErrno;

    _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
}

384
/// @brief Emits a Request through the messageReceived signal.
385
void MockLinkFTP::_sendResponse(uint8_t targetSystemId, uint8_t targetComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
Don Gagne's avatar
Don Gagne committed
386
{
387 388 389
    request->hdr.seqNumber  = seqNumber;
    _lastReplySequence      = seqNumber;
    _lastReplyValid         = true;
390
    
391 392
    mavlink_msg_file_transfer_protocol_pack_chan(_systemIdServer,               // System ID
                                                 _componentIdServer,            // Component ID
393
                                                 _mockLink->mavlinkChannel(),
394 395
                                                 &_lastReply,                   // Mavlink Message to pack into
                                                 0,                             // Target network
396 397
                                                 targetSystemId,
                                                 targetComponentId,
398
                                                 (uint8_t*)request);            // Payload
399

400 401 402 403 404 405
    if (_randomDropsEnabled) {
        if ((rand() % 5) == 0) {
            qDebug() << "MockLinkFTP: Random drop of outgoing packet";
            return;
        }
    }
Don Gagne's avatar
Don Gagne committed
406
    
407
    _mockLink->respondWithMavlinkMessage(_lastReply);
Lorenz Meier's avatar
Lorenz Meier committed
408
}
409 410 411

/// @brief Generates the next sequence number given an incoming sequence number. Handles generating
/// bad sequence numbers when errModeBadSequence is set.
412
uint16_t MockLinkFTP::_nextSeqNumber(uint16_t seqNumber)
413 414 415 416 417 418 419 420
{
    uint16_t outgoingSeqNumber = seqNumber + 1;
    
    if (_errMode == errModeBadSequence) {
        outgoingSeqNumber++;
    }
    return outgoingSeqNumber;
}
421

422
QString MockLinkFTP::_createTestTempFile(int size)
423 424 425
{
    QGCTemporaryFile tmpFile("MockLinkFTPTestCase");
    tmpFile.open(QIODevice::WriteOnly | QIODevice::Truncate);
426
    for (int i=0; i<size; i++) {
427 428 429 430 431
        tmpFile.write(QByteArray(1, i % 255));
    }
    tmpFile.close();
    return tmpFile.fileName();
}