MockLink.cc 42.1 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10 11

#include "MockLink.h"
12
#include "QGCLoggingCategory.h"
13
#include "QGCApplication.h"
14
#ifndef __mobile__
15
#include "UnitTest.h"
16
#endif
17 18 19 20 21 22 23

#include <QTimer>
#include <QDebug>
#include <QFile>

#include <string.h>

Daniel Agar's avatar
Daniel Agar committed
24 25
#include "px4_custom_mode.h"

26
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
Don Gagne's avatar
Don Gagne committed
27
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
28

29 30 31 32 33
/// @file
///     @brief Mock implementation of a Link.
///
///     @author Don Gagne <don@thegagnes.com>

Don Gagne's avatar
Don Gagne committed
34 35 36 37 38
float           MockLink::_vehicleLatitude =        47.633033f;
float           MockLink::_vehicleLongitude =       -122.08794f;
float           MockLink::_vehicleAltitude =        3.5f;
int             MockLink::_nextVehicleSystemId =    128;
const char*     MockLink::_failParam =              "COM_FLTMODE6";
Don Gagne's avatar
Don Gagne committed
39

40
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
41
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
42
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
Don Gagne's avatar
Don Gagne committed
43
const char* MockConfiguration::_failureModeKey =    "FailureMode";
44

45
MockLink::MockLink(MockConfiguration* config)
46
    : _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol())
47 48
    , _name("MockLink")
    , _connected(false)
49 50
    , _vehicleSystemId(_nextVehicleSystemId++)
    , _vehicleComponentId(200)
51
    , _inNSH(false)
Don Gagne's avatar
Don Gagne committed
52
    , _mavlinkStarted(true)
53 54
    , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState(MAV_STATE_STANDBY)
Don Gagne's avatar
Don Gagne committed
55
    , _firmwareType(MAV_AUTOPILOT_PX4)
56
    , _vehicleType(MAV_TYPE_QUADROTOR)
57
    , _fileServer(NULL)
58
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
59
    , _apmSendHomePositionOnEmptyList(false)
Don Gagne's avatar
Don Gagne committed
60
    , _failureMode(MockConfiguration::FailNone)
61 62
    , _sendHomePositionDelayCount(10)   // No home position for 4 seconds
    , _sendGPSPositionDelayCount(100)   // No gps lock for 5 seconds
Don Gagne's avatar
Don Gagne committed
63 64
    , _currentParamRequestListComponentIndex(-1)
    , _currentParamRequestListParamIndex(-1)
65 66
    , _logDownloadCurrentOffset(0)
    , _logDownloadBytesRemaining(0)
67
{
68
    _config = config;
69
    if (_config) {
Don Gagne's avatar
Don Gagne committed
70
        _firmwareType = config->firmwareType();
71
        _vehicleType = config->vehicleType();
72
        _sendStatusText = config->sendStatusText();
Don Gagne's avatar
Don Gagne committed
73
        _failureMode = config->failureMode();
Don Gagne's avatar
Don Gagne committed
74
        _config->setLink(this);
75 76
    }

Don Gagne's avatar
Don Gagne committed
77 78 79 80 81 82
    union px4_custom_mode   px4_cm;

    px4_cm.data = 0;
    px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
    _mavCustomMode = px4_cm.data;

83 84
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
85

86
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
87

88 89 90 91 92
    _loadParams();
}

MockLink::~MockLink(void)
{
93
    _disconnect();
94 95 96
    if (!_logDownloadFilename.isEmpty()) {
        QFile::remove(_logDownloadFilename);
    }
97 98
}

99
bool MockLink::_connect(void)
100
{
101 102 103 104 105
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
106

107 108 109
    return true;
}

Don Gagne's avatar
Don Gagne committed
110
void MockLink::_disconnect(void)
111
{
112 113
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
114 115
        quit();
        wait();
116 117
        emit disconnected();
    }
118 119 120 121
}

void MockLink::run(void)
{
Don Gagne's avatar
Don Gagne committed
122 123 124
    QTimer  timer1HzTasks;
    QTimer  timer10HzTasks;
    QTimer  timer500HzTasks;
125

Don Gagne's avatar
Don Gagne committed
126 127 128
    QObject::connect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
129

Don Gagne's avatar
Don Gagne committed
130 131 132
    timer1HzTasks.start(1000);
    timer10HzTasks.start(100);
    timer500HzTasks.start(2);
133

134
    exec();
135

Don Gagne's avatar
Don Gagne committed
136 137 138
    QObject::disconnect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
dogmaphobic's avatar
dogmaphobic committed
139

140
    _missionItemHandler.shutdown();
141 142 143 144
}

void MockLink::_run1HzTasks(void)
{
145
    if (_mavlinkStarted && _connected) {
146
        _sendHeartBeat();
Don Gagne's avatar
Don Gagne committed
147
        _sendVibration();
148 149 150 151
        if (!qgcApp()->runningUnitTests()) {
            // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
            _sendRCChannels();
        }
152
        if (_sendHomePositionDelayCount > 0) {
153
            // We delay home position for better testing
154 155 156 157
            _sendHomePositionDelayCount--;
        } else {
            _sendHomePosition();
        }
158 159 160 161
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
162 163 164 165 166
    }
}

void MockLink::_run10HzTasks(void)
{
167
    if (_mavlinkStarted && _connected) {
168 169 170 171 172 173
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
174 175 176
    }
}

Don Gagne's avatar
Don Gagne committed
177
void MockLink::_run500HzTasks(void)
178
{
179
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
180
        _paramRequestListWorker();
181
        _logDownloadWorker();
182 183 184 185 186
    }
}

void MockLink::_loadParams(void)
{
187 188 189 190 191
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
            paramFile.setFileName(":/unittest/APMArduPlaneMockLink.params");
192 193
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
            paramFile.setFileName(":/unittest/APMArduSubMockLink.params");
194 195 196 197 198 199 200
        } else {
            paramFile.setFileName(":/unittest/APMArduCopterMockLink.params");
        }
    } else {
        paramFile.setFileName(":/unittest/PX4MockLink.params");
    }

201

202 203 204
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
205

206
    QTextStream paramStream(&paramFile);
207

208 209
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
210

211 212 213
        if (line.startsWith("#")) {
            continue;
        }
214

215 216
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
217

218
        int componentId = paramData.at(1).toInt();
219 220 221
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
222

223 224
        QVariant paramValue;
        switch (paramType) {
225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
        case MAV_PARAM_TYPE_REAL32:
            paramValue = QVariant(valStr.toFloat());
            break;
        case MAV_PARAM_TYPE_UINT32:
            paramValue = QVariant(valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT32:
            paramValue = QVariant(valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT16:
            paramValue = QVariant((quint16)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT16:
            paramValue = QVariant((qint16)valStr.toInt());
            break;
        case MAV_PARAM_TYPE_UINT8:
            paramValue = QVariant((quint8)valStr.toUInt());
            break;
        case MAV_PARAM_TYPE_INT8:
            paramValue = QVariant((qint8)valStr.toUInt());
            break;
        default:
            qCritical() << "Unknown type" << paramType;
            paramValue = QVariant(valStr.toInt());
            break;
250
        }
251

Don Gagne's avatar
Don Gagne committed
252
        qCDebug(MockLinkVerboseLog) << "Loading param" << paramName << paramValue;
253

254
        _mapParamName2Value[componentId][paramName] = paramValue;
255
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
256 257 258 259 260 261 262 263 264 265
    }
}

void MockLink::_sendHeartBeat(void)
{
    mavlink_message_t   msg;

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
Don Gagne's avatar
Don Gagne committed
266
                               _vehicleType,        // MAV_TYPE
Don Gagne's avatar
Don Gagne committed
267
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
268 269
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
270
                               _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
271

272 273
    respondWithMavlinkMessage(msg);
}
274

Don Gagne's avatar
Don Gagne committed
275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

    mavlink_msg_vibration_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               0,       // time_usec
                               50.5,    // vibration_x,
                               10.5,    // vibration_y,
                               60.0,    // vibration_z,
                               1,       // clipping_0
                               2,       // clipping_0
                               3);      // clipping_0

    respondWithMavlinkMessage(msg);
}

293 294 295
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
296

297 298 299 300 301 302
    int cBuffer = mavlink_msg_to_send_buffer(buffer, &msg);
    QByteArray bytes((char *)buffer, cBuffer);
    emit bytesReceived(this, bytes);
}

/// @brief Called when QGC wants to write bytes to the MAV
303
void MockLink::_writeBytes(const QByteArray bytes)
304 305 306 307 308 309 310 311
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
312

313 314 315 316 317 318 319 320
        _handleIncomingMavlinkBytes((uint8_t *)bytes.constData(), bytes.count());
    }
}

/// @brief Handle incoming bytes which are meant to be interpreted by the NuttX shell
void MockLink::_handleIncomingNSHBytes(const char* bytes, int cBytes)
{
    Q_UNUSED(cBytes);
321

322 323 324 325 326 327 328 329
    // Drop back out of NSH
    if (cBytes == 4 && bytes[0] == '\r' && bytes[1] == '\r' && bytes[2] == '\r') {
        _inNSH  = false;
        return;
    }

    if (cBytes > 0) {
        qDebug() << "NSH:" << (const char*)bytes;
330

Don Gagne's avatar
Don Gagne committed
331 332
#if 0
        // MockLink not quite ready to handle this correctly yet
333 334 335 336
        if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
            // This is the mavlink start command
            _mavlinkStarted = true;
        }
Don Gagne's avatar
Don Gagne committed
337
#endif
338 339 340 341 342 343 344 345
    }
}

/// @brief Handle incoming bytes which are meant to be handled by the mavlink protocol
void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
{
    mavlink_message_t msg;
    mavlink_status_t comm;
346

347 348
    for (qint64 i=0; i<cBytes; i++)
    {
349
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
350 351
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
352

353
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
354 355
            continue;
        }
356

357
        switch (msg.msgid) {
358 359 360
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
361

362 363 364
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
365

366 367 368
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
369

370 371 372
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
373

374 375 376
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
377

378 379 380
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
381

382 383 384
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
385

386 387 388
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
389

390 391 392 393 394 395 396 397
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

398 399
        default:
            break;
400 401 402 403 404 405 406
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
407
    qCDebug(MockLinkLog) << "Heartbeat";
408 409 410 411 412 413
}

void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
    mavlink_set_mode_t request;
    mavlink_msg_set_mode_decode(&msg, &request);
414

415
    Q_ASSERT(request.target_system == _vehicleSystemId);
416

417 418 419 420
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
421 422 423 424 425 426 427 428
void MockLink::_handleManualControl(const mavlink_message_t& msg)
{
    mavlink_manual_control_t manualControl;
    mavlink_msg_manual_control_decode(&msg, &manualControl);

    qDebug() << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
}

429
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
430 431
{
    mavlink_param_union_t   valueUnion;
432

433 434
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
435
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
436

437
    valueUnion.param_float = paramFloat;
438

439
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
440

441
    QVariant paramVariant;
442

443
    switch (paramType) {
444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475
    case MAV_PARAM_TYPE_REAL32:
        paramVariant = QVariant::fromValue(valueUnion.param_float);
        break;

    case MAV_PARAM_TYPE_UINT32:
        paramVariant = QVariant::fromValue(valueUnion.param_uint32);
        break;

    case MAV_PARAM_TYPE_INT32:
        paramVariant = QVariant::fromValue(valueUnion.param_int32);
        break;

    case MAV_PARAM_TYPE_UINT16:
        paramVariant = QVariant::fromValue(valueUnion.param_uint16);
        break;

    case MAV_PARAM_TYPE_INT16:
        paramVariant = QVariant::fromValue(valueUnion.param_int16);
        break;

    case MAV_PARAM_TYPE_UINT8:
        paramVariant = QVariant::fromValue(valueUnion.param_uint8);
        break;

    case MAV_PARAM_TYPE_INT8:
        paramVariant = QVariant::fromValue(valueUnion.param_int8);
        break;

    default:
        qCritical() << "Invalid parameter type" << paramType;
        paramVariant = QVariant::fromValue(valueUnion.param_int32);
        break;
476
    }
477

478
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
479
    _mapParamName2Value[componentId][paramName] = paramVariant;
480 481
}

482
/// Convert from a parameter variant to the float value from mavlink_param_union_t
483
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
484
{
485
    mavlink_param_union_t   valueUnion;
486

487 488
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
489
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
490

491
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
492
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
493

494
    switch (paramType) {
495
    case MAV_PARAM_TYPE_REAL32:
496
        valueUnion.param_float = paramVar.toFloat();
497
        break;
498

499 500 501 502 503 504 505
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
506

507 508 509 510 511 512 513
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
514

515 516 517 518 519 520 521
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
522

523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553
    case MAV_PARAM_TYPE_INT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int16 = paramVar.toInt();
        }
        break;

    case MAV_PARAM_TYPE_UINT8:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint8 = paramVar.toUInt();
        }
        break;

    case MAV_PARAM_TYPE_INT8:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
        } else {
            valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
        }
        break;

    default:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        qCritical() << "Invalid parameter type" << paramType;
554
    }
555

556
    return valueUnion.param_float;
557 558 559 560
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
561 562 563 564
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

565
    mavlink_param_request_list_t request;
566

567
    mavlink_msg_param_request_list_decode(&msg, &request);
568

569
    Q_ASSERT(request.target_system == _vehicleSystemId);
570
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
571

Don Gagne's avatar
Don Gagne committed
572 573 574 575
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
576

Don Gagne's avatar
Don Gagne committed
577 578 579 580 581 582 583
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
584

Don Gagne's avatar
Don Gagne committed
585 586 587
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
588

Don Gagne's avatar
Don Gagne committed
589 590 591
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
592

Don Gagne's avatar
Don Gagne committed
593 594
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
595

Don Gagne's avatar
Don Gagne committed
596 597
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
        Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
598

Don Gagne's avatar
Don Gagne committed
599
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
600

Don Gagne's avatar
Don Gagne committed
601 602
        Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
        strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
dogmaphobic's avatar
dogmaphobic committed
603

Don Gagne's avatar
Don Gagne committed
604 605 606 607 608 609 610 611 612 613 614
        qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];

        mavlink_msg_param_value_pack(_vehicleSystemId,
                                     componentId,                                   // component id
                                     &responseMsg,                                  // Outgoing message
                                     paramId,                                       // Parameter name
                                     _floatUnionForParam(componentId, paramName),   // Parameter value
                                     paramType,                                     // MAV_PARAM_TYPE
                                     cParameters,                                   // Total number of parameters
                                     _currentParamRequestListParamIndex);           // Index of this parameter
        respondWithMavlinkMessage(responseMsg);
615
    }
dogmaphobic's avatar
dogmaphobic committed
616

Don Gagne's avatar
Don Gagne committed
617 618 619 620 621 622 623 624
    // Move to next param index
    if (++_currentParamRequestListParamIndex >= cParameters) {
        // We've sent the last parameter for this component, move to next component
        if (++_currentParamRequestListComponentIndex >= _mapParamName2Value.keys().count()) {
            // We've finished sending the last parameter for the last component, request is complete
            _currentParamRequestListComponentIndex = -1;
        } else {
            _currentParamRequestListParamIndex = 0;
625
        }
626 627 628 629 630 631 632
    }
}

void MockLink::_handleParamSet(const mavlink_message_t& msg)
{
    mavlink_param_set_t request;
    mavlink_msg_param_set_decode(&msg, &request);
633

634
    Q_ASSERT(request.target_system == _vehicleSystemId);
635
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
636

637 638
    // Param may not be null terminated if exactly fits
    char paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
Don Gagne's avatar
Don Gagne committed
639
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
640
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
641

Don Gagne's avatar
Don Gagne committed
642
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
dogmaphobic's avatar
dogmaphobic committed
643

644 645
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
646
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
647

648
    // Save the new value
649
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
650

651 652 653
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
654 655 656 657 658 659 660
                                 componentId,                                               // component id
                                 &responseMsg,                                              // Outgoing message
                                 paramId,                                                   // Parameter name
                                 request.param_value,                                       // Send same value back
                                 request.param_type,                                        // Send same type back
                                 _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                 _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
661
    respondWithMavlinkMessage(responseMsg);
662 663 664 665
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
666
    mavlink_message_t   responseMsg;
667 668
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
669

Don Gagne's avatar
Don Gagne committed
670
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
671
    int componentId = request.target_component;
672 673

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
674
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
        mavlink_msg_param_value_pack(_vehicleSystemId,
                                     componentId,
                                     &responseMsg,
                                     request.param_id,
                                     valueUnion.param_float,
                                     MAV_PARAM_TYPE_UINT32,
                                     0,
                                     -1);
        respondWithMavlinkMessage(responseMsg);
        return;
    }

691
    Q_ASSERT(_mapParamName2Value.contains(componentId));
692

693 694
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
695

696
    Q_ASSERT(request.target_system == _vehicleSystemId);
697

698 699 700
    if (request.param_index == -1) {
        // Request is by param name. Param may not be null terminated if exactly fits
        strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
701
    } else {
702
        // Request is by index
703

704
        Q_ASSERT(request.param_index >= 0 && request.param_index < _mapParamName2Value[componentId].count());
705

706
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
707 708
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
709
    }
710

711
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
712
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
713

Don Gagne's avatar
Don Gagne committed
714 715 716 717 718 719
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

720
    mavlink_msg_param_value_pack(_vehicleSystemId,
721 722 723 724 725 726 727
                                 componentId,                                               // component id
                                 &responseMsg,                                              // Outgoing message
                                 paramId,                                                   // Parameter name
                                 _floatUnionForParam(componentId, paramId),                 // Parameter value
                                 _mapParamName2MavParamType[paramId],                       // Parameter type
                                 _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                 _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
728
    respondWithMavlinkMessage(responseMsg);
729 730
}

731 732 733
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
734

735 736 737 738
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
739

740 741 742 743 744 745 746
    mavlink_message_t responseMsg;
    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &responseMsg,          // Outgoing message
                                 0,                     // time since boot, ignored
                                 18,                    // channel count
                                 chanRaw[0],            // channel raw value
747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764
            chanRaw[1],            // channel raw value
            chanRaw[2],            // channel raw value
            chanRaw[3],            // channel raw value
            chanRaw[4],            // channel raw value
            chanRaw[5],            // channel raw value
            chanRaw[6],            // channel raw value
            chanRaw[7],            // channel raw value
            chanRaw[8],            // channel raw value
            chanRaw[9],            // channel raw value
            chanRaw[10],           // channel raw value
            chanRaw[11],           // channel raw value
            chanRaw[12],           // channel raw value
            chanRaw[13],           // channel raw value
            chanRaw[14],           // channel raw value
            chanRaw[15],           // channel raw value
            chanRaw[16],           // channel raw value
            chanRaw[17],           // channel raw value
            0);                    // rss
765 766 767 768 769 770 771
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
772
}
773 774 775 776

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
    mavlink_command_long_t request;
777
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
778

779 780
    mavlink_msg_command_long_decode(&msg, &request);

781 782
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
783 784 785 786 787
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
788
        commandResult = MAV_RESULT_ACCEPTED;
789 790
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
791 792 793
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
794 795 796
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
797 798 799 800
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
801
    }
802 803 804 805 806 807 808 809

    mavlink_message_t commandAck;
    mavlink_msg_command_ack_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &commandAck,
                                 request.command,
                                 commandResult);
    respondWithMavlinkMessage(commandAck);
810 811
}

812 813 814 815
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
816 817 818 819 820 821 822 823 824 825 826 827 828
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        flightVersion |= 3 << (8*3);
        flightVersion |= 3 << (8*2);
        flightVersion |= 0 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    }
829 830 831 832

    mavlink_msg_autopilot_version_pack(_vehicleSystemId,
                                       _vehicleComponentId,
                                       &msg,
Don Gagne's avatar
Don Gagne committed
833 834 835 836 837 838 839 840 841 842 843
                                       0,                               // capabilities,
                                       flightVersion,                   // flight_sw_version,
                                       0,                               // middleware_sw_version,
                                       0,                               // os_sw_version,
                                       0,                               // board_version,
                                       (uint8_t *)&customVersion,       // flight_custom_version,
                                       (uint8_t *)&customVersion,       // middleware_custom_version,
                                       (uint8_t *)&customVersion,       // os_custom_version,
                                       0,                               // vendor_id,
                                       0,                               // product_id,
                                       0);                              // uid
844 845 846
    respondWithMavlinkMessage(msg);
}

847
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
848
{
849
    _missionItemHandler.setMissionItemFailureMode(failureMode);
850
}
851 852 853

void MockLink::_sendHomePosition(void)
{
854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871
    mavlink_message_t msg;

    float bogus[4];
    bogus[0] = 0.0f;
    bogus[1] = 0.0f;
    bogus[2] = 0.0f;
    bogus[3] = 0.0f;

    mavlink_msg_home_position_pack(_vehicleSystemId,
                                   _vehicleComponentId,
                                   &msg,
                                   (int32_t)(_vehicleLatitude * 1E7),
                                   (int32_t)(_vehicleLongitude * 1E7),
                                   (int32_t)(_vehicleAltitude * 1000),
                                   0.0f, 0.0f, 0.0f,
                                   &bogus[0],
            0.0f, 0.0f, 0.0f);
    respondWithMavlinkMessage(msg);
872
}
Don Gagne's avatar
Don Gagne committed
873 874 875 876 877 878 879 880 881 882 883

void MockLink::_sendGpsRawInt(void)
{
    static uint64_t timeTick = 0;
    mavlink_message_t msg;

    mavlink_msg_gps_raw_int_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &msg,
                                 timeTick++,                            // time since boot
                                 3,                                     // 3D fix
dogmaphobic's avatar
dogmaphobic committed
884
                                 (int32_t)(_vehicleLatitude  * 1E7),
Don Gagne's avatar
Don Gagne committed
885
                                 (int32_t)(_vehicleLongitude * 1E7),
dogmaphobic's avatar
dogmaphobic committed
886
                                 (int32_t)(_vehicleAltitude  * 1000),
Don Gagne's avatar
Don Gagne committed
887 888 889 890 891 892
                                 UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                 UINT16_MAX,                            // velocity not known
                                 UINT16_MAX,                            // course over ground not known
                                 8);                                    // satellite count
    respondWithMavlinkMessage(msg);
}
893

894 895 896 897 898 899 900 901
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
902 903 904 905 906 907 908 909 910 911
    { MAV_SEVERITY_INFO,        "#Testing audio output" },
    { MAV_SEVERITY_EMERGENCY,   "Status text emergency" },
    { MAV_SEVERITY_ALERT,       "Status text alert" },
    { MAV_SEVERITY_CRITICAL,    "Status text critical" },
    { MAV_SEVERITY_ERROR,       "Status text error" },
    { MAV_SEVERITY_WARNING,     "Status text warning" },
    { MAV_SEVERITY_NOTICE,      "Status text notice" },
    { MAV_SEVERITY_INFO,        "Status text info" },
    { MAV_SEVERITY_DEBUG,       "Status text debug" },
};
912 913 914 915 916 917 918 919 920 921 922 923 924 925

    for (size_t i=0; i<sizeof(rgMessages)/sizeof(rgMessages[0]); i++) {
        mavlink_message_t msg;
        const struct StatusMessage* status = &rgMessages[i];

        mavlink_msg_statustext_pack(_vehicleSystemId,
                                    _vehicleComponentId,
                                    &msg,
                                    status->severity,
                                    status->msg);
        respondWithMavlinkMessage(msg);
    }
}

926 927 928
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
929
    , _vehicleType(MAV_TYPE_QUADROTOR)
930
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
931
    , _failureMode(FailNone)
932 933 934 935 936 937 938
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
939
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
940
    _vehicleType =      source->_vehicleType;
941
    _sendStatusText =   source->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
942
    _failureMode =      source->_failureMode;
943 944 945 946 947 948
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
949 950 951 952 953 954 955

    if (!usource) {
        qWarning() << "dynamic_cast failed" << source << usource;
        return;
    }

    _firmwareType =     usource->_firmwareType;
956
    _vehicleType =      usource->_vehicleType;
957
    _sendStatusText =   usource->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
958
    _failureMode =      usource->_failureMode;
959 960 961 962 963 964
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
965
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
966
    settings.setValue(_sendStatusTextKey, _sendStatusText);
Don Gagne's avatar
Don Gagne committed
967
    settings.setValue(_failureModeKey, (int)_failureMode);
968 969 970 971 972 973 974 975
    settings.sync();
    settings.endGroup();
}

void MockConfiguration::loadSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    _firmwareType = (MAV_AUTOPILOT)settings.value(_firmwareTypeKey, (int)MAV_AUTOPILOT_PX4).toInt();
976
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
977
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
978
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
979 980 981 982 983 984 985 986 987
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
988
            qWarning() << "updateSettings not supported";
989 990 991 992
            //ulink->_restartConnection();
        }
    }
}
993 994 995 996 997 998 999 1000 1001 1002 1003

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
    LinkManager* linkManager = qgcApp()->toolbox()->linkManager();

    mockConfig->setDynamic(true);
    linkManager->linkConfigurations()->append(mockConfig);

    return qobject_cast<MockLink*>(linkManager->createConnectedLink(mockConfig));
}

Don Gagne's avatar
Don Gagne committed
1004
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1005 1006 1007 1008 1009 1010
{
    MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1011
    mockConfig->setFailureMode(failureMode);
1012 1013 1014 1015

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1016
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1017 1018 1019 1020 1021 1022
{
    MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1023
    mockConfig->setFailureMode(failureMode);
1024 1025 1026 1027

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1028
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1029 1030 1031 1032 1033 1034
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1035
    mockConfig->setFailureMode(failureMode);
1036 1037 1038 1039

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1040
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1041 1042 1043 1044 1045 1046
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1047
    mockConfig->setFailureMode(failureMode);
1048 1049 1050 1051

    return _startMockLink(mockConfig);
}

1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduSub MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_SUBMARINE);
    mockConfig->setSendStatusText(sendStatusText);
    mockConfig->setFailureMode(failureMode);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &msg,
                                 0,                     // time_boot_ms
                                 8,                     // chancount
                                 1500,                  // chan1_raw
                                 1500,                  // chan2_raw
                                 1500,                  // chan3_raw
                                 1500,                  // chan4_raw
                                 1500,                  // chan5_raw
                                 1500,                  // chan6_raw
                                 1500,                  // chan7_raw
                                 1500,                  // chan8_raw
                                 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
                                 0);                    // rssi

    respondWithMavlinkMessage(msg);

}
1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116

void MockLink::_handlePreFlightCalibration(const mavlink_command_long_t& request)
{
    const char* pCalMessage;
    static const char* gyroCalResponse = "[cal] calibration started: 2 gyro";
    static const char* magCalResponse = "[cal] calibration started: 2 mag";
    static const char* accelCalResponse = "[cal] calibration started: 2 accel";

    if (request.param1 == 1) {
        // Gyro cal
        pCalMessage = gyroCalResponse;
    } else if (request.param2 == 1) {
        // Mag cal
        pCalMessage = magCalResponse;
    } else if (request.param5 == 1) {
        // Accel cal
        pCalMessage = accelCalResponse;
    } else {
        return;
    }

    mavlink_message_t msg;
    mavlink_msg_statustext_pack(_vehicleSystemId,
                                _vehicleComponentId,
                                &msg,
                                MAV_SEVERITY_INFO,
                                pCalMessage);
    respondWithMavlinkMessage(msg);
}

1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146
void MockLink::_handleLogRequestList(const mavlink_message_t& msg)
{
    mavlink_log_request_list_t request;

    mavlink_msg_log_request_list_decode(&msg, &request);

    if (request.start != 0 && request.end != 0xffff) {
        qWarning() << "MockLink::_handleLogRequestList cannot handle partial requests";
        return;
    }

    mavlink_message_t responseMsg;
    mavlink_msg_log_entry_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &responseMsg,
                               _logDownloadLogId,       // log id
                               1,                       // num_logs
                               1,                       // last_log_num
                               0,                       // time_utc
                               _logDownloadFileSize);   // size
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleLogRequestData(const mavlink_message_t& msg)
{
    mavlink_log_request_data_t request;

    mavlink_msg_log_request_data_decode(&msg, &request);

    if (_logDownloadFilename.isEmpty()) {
1147
        #ifndef __mobile__
1148
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1149
        #endif
1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201
    }

    if (request.id != 0) {
        qWarning() << "MockLink::_handleLogRequestData id must be 0";
        return;
    }

    if (request.ofs > _logDownloadFileSize - 1) {
        qWarning() << "MockLink::_handleLogRequestData offset past end of file request.ofs:size" << request.ofs << _logDownloadFileSize;
        return;
    }

    // This will trigger _logDownloadWorker to send data
    _logDownloadCurrentOffset = request.ofs;
    if (request.ofs + request.count > _logDownloadFileSize) {
        request.count = _logDownloadFileSize - request.ofs;
    }
    _logDownloadBytesRemaining = request.count;
}

void MockLink::_logDownloadWorker(void)
{
    if (_logDownloadBytesRemaining != 0) {
        QFile file(_logDownloadFilename);
        if (file.open(QIODevice::ReadOnly)) {
            uint8_t buffer[MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN];

            qint64 bytesToRead = qMin(_logDownloadBytesRemaining, (uint32_t)MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
            Q_ASSERT(file.seek(_logDownloadCurrentOffset));
            Q_ASSERT(file.read((char *)buffer, bytesToRead) == bytesToRead);

            qDebug() << "MockLink::_logDownloadWorker" << _logDownloadCurrentOffset << _logDownloadBytesRemaining;

            mavlink_message_t responseMsg;
            mavlink_msg_log_data_pack(_vehicleSystemId,
                                       _vehicleComponentId,
                                       &responseMsg,
                                       _logDownloadLogId,
                                       _logDownloadCurrentOffset,
                                       bytesToRead,
                                       &buffer[0]);
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

            file.close();
        } else {
            qWarning() << "MockLink::_logDownloadWorker open failed" << file.errorString();
        }
    }
}