MockLinkFTP.cc 16.7 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
    } else if (path == "/version.json.gz") {
        tmpFilename = ":MockLink/Version.MetaData.json.gz";
    } else if (path == "/parameter.json") {
        tmpFilename = ":MockLink/Parameter.MetaData.json";
126 127
    }

128 129 130 131 132 133 134 135
    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);
136 137 138
        return;
    }
    
139 140 141
    response.hdr.opcode     = MavlinkFTP::kRspAck;
    response.hdr.req_opcode = MavlinkFTP::kCmdOpenFileRO;
    response.hdr.session    = _sessionId;
142
    
143 144
    // Data contains file length
    response.hdr.size = sizeof(uint32_t);
145
    response.openFileLength = _currentFile.size();
146
    
147
    _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
148 149
}

150
void MockLinkFTP::_readCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
151
{
152 153
    MavlinkFTP::Request	response;
    uint16_t			outgoingSeqNumber = _nextSeqNumber(seqNumber);
154 155

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

162 163 164 165
    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
166
            _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
167 168 169 170 171 172 173
            return;
        } else if (_errMode == errModeNoSecondResponse) {
            // No rsponse for all subsequent requests
            return;
        }
    }
    
174 175
    if (readOffset >= _currentFile.size()) {
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdReadFile);
176 177 178
        return;
    }
    
179 180 181 182
    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);
183
    
184
    // We should always have written something, otherwise there is something wrong with the code above
185
    Q_ASSERT(cBytesToRead);
186
    
187 188 189 190 191
    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;
192

193
    _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
194 195
}

196
void MockLinkFTP::_burstReadCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
197
{
198 199
    uint16_t            outgoingSeqNumber = _nextSeqNumber(seqNumber);
    MavlinkFTP::Request response;
200 201

    if (request->hdr.session != _sessionId) {
202
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrFail, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
203 204 205
        return;
    }
    
206 207 208
    int         burstMax    = 10;
    int         burstCount  = 1;
    uint32_t    burstOffset = request->hdr.offset;
209
    
210 211 212 213 214
    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);
215

216
        // We should always have written something, otherwise there is something wrong with the code above
217 218 219 220 221 222 223 224 225 226 227
        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;

228
        _sendResponse(senderSystemId, senderComponentId, &response, outgoingSeqNumber);
229 230
        
        outgoingSeqNumber = _nextSeqNumber(outgoingSeqNumber);
231
        burstOffset += cBytes;
232
    }
233

234
    _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrEOF, outgoingSeqNumber, MavlinkFTP::kCmdBurstReadFile);
235 236
}

237
void MockLinkFTP::_terminateCommand(uint8_t senderSystemId, uint8_t senderComponentId, MavlinkFTP::Request* request, uint16_t seqNumber)
238
{
239 240
    uint16_t outgoingSeqNumber = _nextSeqNumber(seqNumber);

241
    if (request->hdr.session != _sessionId) {
242
        _sendNak(senderSystemId, senderComponentId, MavlinkFTP::kErrInvalidSession, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
243 244 245
        return;
    }
    
246
    _sendAck(senderSystemId, senderComponentId, outgoingSeqNumber, MavlinkFTP::kCmdTerminateSession);
247

248 249 250
    emit terminateCommandReceived();
}

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

262
void MockLinkFTP::mavlinkMessageReceived(const mavlink_message_t& message)
263 264 265 266
{
    if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
        return;
    }
267
    
268
    MavlinkFTP::Request  ackResponse;
269

270 271 272 273 274 275
    mavlink_file_transfer_protocol_t requestFTP;
    mavlink_msg_file_transfer_protocol_decode(&message, &requestFTP);
    
    if (requestFTP.target_system != _systemIdServer) {
        return;
    }
276

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

279 280 281 282 283 284 285 286 287 288 289 290 291 292
    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;
    }
293

294
    uint16_t incomingSeqNumber = request->hdr.seqNumber;
295 296
    uint16_t outgoingSeqNumber = _nextSeqNumber(incomingSeqNumber);
    
297
    if (request->hdr.opcode != MavlinkFTP::kCmdResetSessions && request->hdr.opcode != MavlinkFTP::kCmdTerminateSession) {
298 299 300 301 302
        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
303
            _sendNak(message.sysid, message.compid, MavlinkFTP::kErrFail, outgoingSeqNumber, (MavlinkFTP::OpCode_t)request->hdr.opcode);
304 305
            return;
        }
306
    }
307

Don Gagne's avatar
Don Gagne committed
308
    switch (request->hdr.opcode) {
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 341 342 343 344
    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;
345 346
    }
}
Don Gagne's avatar
Don Gagne committed
347

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

361
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
362
{
363
    MavlinkFTP::Request nakResponse;
Don Gagne's avatar
Don Gagne committed
364

365 366 367 368 369
    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
370
    
371
    _sendResponse(targetSystemId, targetComponentId, &nakResponse, seqNumber);
Don Gagne's avatar
Don Gagne committed
372 373
}

374 375 376 377 378 379 380 381 382 383 384 385 386 387
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);
}

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

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

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

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