MockLink.cc 43.8 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 15 16

#ifdef UNITTEST_BUILD
    #include "UnitTest.h"
17
#endif
18 19 20 21 22 23 24

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

#include <string.h>

25 26
// FIXME: Hack to work around clean headers
#include "FirmwarePlugin/PX4/px4_custom_mode.h"
Daniel Agar's avatar
Daniel Agar committed
27

28
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
Don Gagne's avatar
Don Gagne committed
29
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
30

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

Don Gagne's avatar
Don Gagne committed
36 37 38 39 40
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
41

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

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

Don Gagne's avatar
Don Gagne committed
79 80 81 82 83 84
    union px4_custom_mode   px4_cm;

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

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

88
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
89

90 91 92 93 94
    _loadParams();
}

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

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

109 110 111
    return true;
}

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

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

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

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

136
    exec();
137

Don Gagne's avatar
Don Gagne committed
138 139 140
    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
141

142
    _missionItemHandler.shutdown();
143 144 145 146
}

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

void MockLink::_run10HzTasks(void)
{
168
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
169
        _sendHeartBeat();
170 171 172 173 174 175
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
176 177 178
    }
}

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

void MockLink::_loadParams(void)
{
189 190 191 192 193
    QFile paramFile;

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

203

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

208
    QTextStream paramStream(&paramFile);
209

210 211
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
212

213 214 215
        if (line.startsWith("#")) {
            continue;
        }
216

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

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

225 226
        QVariant paramValue;
        switch (paramType) {
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251
        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;
252
        }
253

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

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

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

265 266 267 268 269 270 271 272 273
    mavlink_msg_heartbeat_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
                                    mavlinkChannel(),
                                    &msg,
                                    _vehicleType,        // MAV_TYPE
                                    _firmwareType,      // MAV_AUTOPILOT
                                    _mavBaseMode,        // MAV_MODE
                                    _mavCustomMode,      // custom mode
                                    _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
274

275 276
    respondWithMavlinkMessage(msg);
}
277

Don Gagne's avatar
Don Gagne committed
278 279 280 281
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

282 283 284 285 286 287 288 289 290 291 292
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
                                    mavlinkChannel(),
                                    &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
Don Gagne's avatar
Don Gagne committed
293 294 295 296

    respondWithMavlinkMessage(msg);
}

297 298 299
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
300

301 302 303 304 305 306
    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
307
void MockLink::_writeBytes(const QByteArray bytes)
308 309 310 311 312 313 314 315
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
316

317 318 319 320 321 322 323 324
        _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);
325

326 327 328 329 330 331 332 333
    // 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;
334

Don Gagne's avatar
Don Gagne committed
335 336
#if 0
        // MockLink not quite ready to handle this correctly yet
337 338 339 340
        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
341
#endif
342 343 344 345 346 347 348 349
    }
}

/// @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;
350

351 352
    for (qint64 i=0; i<cBytes; i++)
    {
353
        if (!mavlink_parse_char(mavlinkChannel(), bytes[i], &msg, &comm)) {
354 355
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
356

357
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
358 359
            continue;
        }
360

361
        switch (msg.msgid) {
362 363 364
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
365

366 367 368
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
369

370 371 372
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
373

374 375 376
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
377

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

382 383 384
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
385

386 387 388
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
389

390 391 392
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
393

394 395 396 397 398 399 400 401
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

402 403
        default:
            break;
404 405 406 407 408 409 410
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
411
    qCDebug(MockLinkLog) << "Heartbeat";
412 413 414 415 416 417
}

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

419
    Q_ASSERT(request.target_system == _vehicleSystemId);
420

421 422 423 424
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
425 426 427 428 429 430 431 432
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;
}

433
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
434 435
{
    mavlink_param_union_t   valueUnion;
436

437 438
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
439
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
440

441
    valueUnion.param_float = paramFloat;
442

443
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
444

445
    QVariant paramVariant;
446

447
    switch (paramType) {
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 476 477 478 479
    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;
480
    }
481

482
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
483
    _mapParamName2Value[componentId][paramName] = paramVariant;
484 485
}

486
/// Convert from a parameter variant to the float value from mavlink_param_union_t
487
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
488
{
489
    mavlink_param_union_t   valueUnion;
490

491 492
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
493
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
494

495
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
496
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
497

498
    switch (paramType) {
499
    case MAV_PARAM_TYPE_REAL32:
500
        valueUnion.param_float = paramVar.toFloat();
501
        break;
502

503 504 505 506 507 508 509
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
510

511 512 513 514 515 516 517
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
518

519 520 521 522 523 524 525
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
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 554 555 556 557
    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;
558
    }
559

560
    return valueUnion.param_float;
561 562 563 564
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
565 566 567 568
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

569
    mavlink_param_request_list_t request;
570

571
    mavlink_msg_param_request_list_decode(&msg, &request);
572

573
    Q_ASSERT(request.target_system == _vehicleSystemId);
574
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
575

Don Gagne's avatar
Don Gagne committed
576 577 578 579
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
580

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

Don Gagne's avatar
Don Gagne committed
589 590 591
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
592

Don Gagne's avatar
Don Gagne committed
593 594 595
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
596

Don Gagne's avatar
Don Gagne committed
597 598
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
599

Don Gagne's avatar
Don Gagne committed
600 601
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
        Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
602

Don Gagne's avatar
Don Gagne committed
603
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
604

Don Gagne's avatar
Don Gagne committed
605 606
        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
607

Don Gagne's avatar
Don Gagne committed
608 609
        qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];

610 611 612 613 614 615 616 617 618
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
                                          mavlinkChannel(),
                                          &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
Don Gagne's avatar
Don Gagne committed
619
        respondWithMavlinkMessage(responseMsg);
620
    }
dogmaphobic's avatar
dogmaphobic committed
621

Don Gagne's avatar
Don Gagne committed
622 623 624 625 626 627 628 629
    // 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;
630
        }
631 632 633 634 635 636 637
    }
}

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

639
    Q_ASSERT(request.target_system == _vehicleSystemId);
640
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
641

642 643
    // 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
644
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
645
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
646

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

649 650
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
651
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
652

653
    // Save the new value
654
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
655

656 657
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
658 659 660 661 662 663 664 665 666
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
                                      mavlinkChannel(),
                                      &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
667
    respondWithMavlinkMessage(responseMsg);
668 669 670 671
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
672
    mavlink_message_t   responseMsg;
673 674
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
675

Don Gagne's avatar
Don Gagne committed
676
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
677
    int componentId = request.target_component;
678 679

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
680
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
681 682 683 684
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
685 686 687 688 689 690 691 692 693
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
                                          mavlinkChannel(),
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
694 695 696 697
        respondWithMavlinkMessage(responseMsg);
        return;
    }

698
    Q_ASSERT(_mapParamName2Value.contains(componentId));
699

700 701
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
702

703
    Q_ASSERT(request.target_system == _vehicleSystemId);
704

705 706 707
    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);
708
    } else {
709
        // Request is by index
710

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

713
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
714 715
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
716
    }
717

718
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
719
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
720

Don Gagne's avatar
Don Gagne committed
721 722 723 724 725 726
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

727 728 729 730 731 732 733 734 735
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
                                      mavlinkChannel(),
                                      &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
736
    respondWithMavlinkMessage(responseMsg);
737 738
}

739 740 741
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
742

743 744 745 746
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
747

748
    mavlink_message_t responseMsg;
749 750 751 752 753 754 755
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
                                      mavlinkChannel(),
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773
            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
774 775 776 777 778 779 780
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
781
}
782 783 784 785

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

788 789
    mavlink_msg_command_long_decode(&msg, &request);

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

    mavlink_message_t commandAck;
813 814 815 816 817 818
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
                                      mavlinkChannel(),
                                      &commandAck,
                                      request.command,
                                      commandResult);
819
    respondWithMavlinkMessage(commandAck);
820 821
}

822 823 824 825
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
826 827 828 829 830 831 832 833 834 835 836 837 838
    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);
    }
839

840 841 842 843 844 845 846 847 848 849 850 851 852 853 854
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
                                            mavlinkChannel(),
                                            &msg,
                                            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
855 856 857
    respondWithMavlinkMessage(msg);
}

858
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
859
{
860
    _missionItemHandler.setMissionItemFailureMode(failureMode);
861
}
862 863 864

void MockLink::_sendHomePosition(void)
{
865 866 867 868 869 870 871 872
    mavlink_message_t msg;

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

873 874 875 876 877 878 879 880 881
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
                                        mavlinkChannel(),
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
882 883
            0.0f, 0.0f, 0.0f);
    respondWithMavlinkMessage(msg);
884
}
Don Gagne's avatar
Don Gagne committed
885 886 887 888 889 890

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

891 892 893 894 895 896 897 898 899 900 901 902 903
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
                                      mavlinkChannel(),
                                      &msg,
                                      timeTick++,                            // time since boot
                                      3,                                     // 3D fix
                                      (int32_t)(_vehicleLatitude  * 1E7),
                                      (int32_t)(_vehicleLongitude * 1E7),
                                      (int32_t)(_vehicleAltitude  * 1000),
                                      UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                      UINT16_MAX,                            // velocity not known
                                      UINT16_MAX,                            // course over ground not known
                                      8);                                    // satellite count
Don Gagne's avatar
Don Gagne committed
904 905
    respondWithMavlinkMessage(msg);
}
906

907 908 909 910 911 912 913 914
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
915 916 917 918 919 920 921 922 923 924
    { 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" },
};
925 926 927 928 929

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

930 931 932 933 934 935
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
                                         mavlinkChannel(),
                                         &msg,
                                         status->severity,
                                         status->msg);
936 937 938 939
        respondWithMavlinkMessage(msg);
    }
}

940 941 942
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
943
    , _vehicleType(MAV_TYPE_QUADROTOR)
944
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
945
    , _failureMode(FailNone)
946 947 948 949 950 951 952
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
953
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
954
    _vehicleType =      source->_vehicleType;
955
    _sendStatusText =   source->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
956
    _failureMode =      source->_failureMode;
957 958 959 960 961 962
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
963 964 965 966 967 968 969

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

    _firmwareType =     usource->_firmwareType;
970
    _vehicleType =      usource->_vehicleType;
971
    _sendStatusText =   usource->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
972
    _failureMode =      usource->_failureMode;
973 974 975 976 977 978
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
979
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
980
    settings.setValue(_sendStatusTextKey, _sendStatusText);
Don Gagne's avatar
Don Gagne committed
981
    settings.setValue(_failureModeKey, (int)_failureMode);
982 983 984 985 986 987 988 989
    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();
990
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
991
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
992
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
993 994 995 996 997 998 999 1000 1001
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1002
            qWarning() << "updateSettings not supported";
1003 1004 1005 1006
            //ulink->_restartConnection();
        }
    }
}
1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017

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
1018
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1019 1020 1021 1022 1023 1024
{
    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
1025
    mockConfig->setFailureMode(failureMode);
1026 1027 1028 1029

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1030
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1031 1032 1033 1034 1035 1036
{
    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
1037
    mockConfig->setFailureMode(failureMode);
1038 1039 1040 1041

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1042
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1043 1044 1045 1046 1047 1048
{
    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
1049
    mockConfig->setFailureMode(failureMode);
1050 1051 1052 1053

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1054
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1055 1056 1057 1058 1059 1060
{
    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
1061
    mockConfig->setFailureMode(failureMode);
1062 1063 1064 1065

    return _startMockLink(mockConfig);
}

1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077
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
1078 1079 1080 1081
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
                                      mavlinkChannel(),
                                      &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
Don Gagne's avatar
Don Gagne committed
1098 1099 1100 1101

    respondWithMavlinkMessage(msg);

}
1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123

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;
1124 1125 1126 1127 1128 1129
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
                                     mavlinkChannel(),
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1130 1131 1132
    respondWithMavlinkMessage(msg);
}

1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144
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;
1145 1146 1147 1148 1149 1150 1151 1152 1153
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
                                    mavlinkChannel(),
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163
    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()) {
1164
        #ifdef UNITTEST_BUILD
1165
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1166
        #endif
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
    }

    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;
1201 1202 1203 1204 1205 1206 1207 1208
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
                                           mavlinkChannel(),
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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