MockLink.cc 49.9 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>

36 37 38 39 40 41 42
// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
// testing of a gazebo vehicle and a mocklink vehicle
double      MockLink::_defaultVehicleLatitude =     47.397f;
double      MockLink::_defaultVehicleLongitude =    8.5455f;
double      MockLink::_defaultVehicleAltitude =     488.056f;
int         MockLink::_nextVehicleSystemId =        128;
const char* MockLink::_failParam =                  "COM_FLTMODE6";
Don Gagne's avatar
Don Gagne committed
43

44
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
45
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
46
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
47
const char* MockConfiguration::_highLatencyKey =    "HighLatency";
Don Gagne's avatar
Don Gagne committed
48
const char* MockConfiguration::_failureModeKey =    "FailureMode";
49

50
MockLink::MockLink(SharedLinkConfigurationPointer& config)
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
    : LinkInterface                         (config)
    , _missionItemHandler                   (this, qgcApp()->toolbox()->mavlinkProtocol())
    , _name                                 ("MockLink")
    , _connected                            (false)
    , _mavlinkChannel                       (0)
    , _vehicleSystemId                      (_nextVehicleSystemId++)
    , _vehicleComponentId                   (MAV_COMP_ID_AUTOPILOT1)
    , _inNSH                                (false)
    , _mavlinkStarted                       (true)
    , _mavBaseMode                          (MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState                             (MAV_STATE_STANDBY)
    , _firmwareType                         (MAV_AUTOPILOT_PX4)
    , _vehicleType                          (MAV_TYPE_QUADROTOR)
    , _vehicleLatitude                      (_defaultVehicleLatitude + ((_vehicleSystemId - 128) * 0.0001))     // Slight offset for each vehicle
    , _vehicleLongitude                     (_defaultVehicleLongitude + ((_vehicleSystemId - 128) * 0.0001))
    , _vehicleAltitude                      (_defaultVehicleAltitude)
    , _fileServer                           (NULL)
    , _sendStatusText                       (false)
    , _apmSendHomePositionOnEmptyList       (false)
    , _failureMode                          (MockConfiguration::FailNone)
    , _sendHomePositionDelayCount           (10)    // No home position for 4 seconds
    , _sendGPSPositionDelayCount            (100)   // No gps lock for 5 seconds
Don Gagne's avatar
Don Gagne committed
73
    , _currentParamRequestListComponentIndex(-1)
74 75 76
    , _currentParamRequestListParamIndex    (-1)
    , _logDownloadCurrentOffset             (0)
    , _logDownloadBytesRemaining            (0)
77
    , _adsbAngle                            (0)
78
{
79 80 81 82
    MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(_config.data());
    _firmwareType = mockConfig->firmwareType();
    _vehicleType = mockConfig->vehicleType();
    _sendStatusText = mockConfig->sendStatusText();
83
    _highLatency = mockConfig->highLatency();
84
    _failureMode = mockConfig->failureMode();
85

Don Gagne's avatar
Don Gagne committed
86 87 88 89 90 91
    union px4_custom_mode   px4_cm;

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

92 93
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
94

95
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
96

97
    _loadParams();
98 99 100

    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(1000, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);
101 102 103 104
}

MockLink::~MockLink(void)
{
105
    _disconnect();
106 107 108
    if (!_logDownloadFilename.isEmpty()) {
        QFile::remove(_logDownloadFilename);
    }
109 110
}

111
bool MockLink::_connect(void)
112
{
113 114
    if (!_connected) {
        _connected = true;
115 116 117 118 119 120 121 122
        _mavlinkChannel = qgcApp()->toolbox()->linkManager()->_reserveMavlinkChannel();
        if (_mavlinkChannel == 0) {
            qWarning() << "No mavlink channels available";
            return false;
        }
        // MockLinks use Mavlink 2.0
        mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(_mavlinkChannel);
        mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
123 124 125
        start();
        emit connected();
    }
126

127 128 129
    return true;
}

Don Gagne's avatar
Don Gagne committed
130
void MockLink::_disconnect(void)
131
{
132
    if (_connected) {
133 134 135
        if (_mavlinkChannel != 0) {
            qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
        }
136
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
137 138
        quit();
        wait();
139 140
        emit disconnected();
    }
141 142 143 144
}

void MockLink::run(void)
{
Don Gagne's avatar
Don Gagne committed
145 146 147
    QTimer  timer1HzTasks;
    QTimer  timer10HzTasks;
    QTimer  timer500HzTasks;
148

Don Gagne's avatar
Don Gagne committed
149 150 151
    QObject::connect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
152

Don Gagne's avatar
Don Gagne committed
153 154 155
    timer1HzTasks.start(1000);
    timer10HzTasks.start(100);
    timer500HzTasks.start(2);
156

157
    exec();
158

Don Gagne's avatar
Don Gagne committed
159 160 161
    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
162

163
    _missionItemHandler.shutdown();
164 165 166 167
}

void MockLink::_run1HzTasks(void)
{
168
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
169
        _sendVibration();
170
        _sendADSBVehicles();
171 172 173 174
        if (!qgcApp()->runningUnitTests()) {
            // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
            _sendRCChannels();
        }
175
        if (_sendHomePositionDelayCount > 0) {
176
            // We delay home position for better testing
177 178 179 180
            _sendHomePositionDelayCount--;
        } else {
            _sendHomePosition();
        }
181 182 183 184
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
185 186 187 188 189
    }
}

void MockLink::_run10HzTasks(void)
{
190
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
191
        _sendHeartBeat();
192 193 194 195 196 197
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
198 199 200
    }
}

Don Gagne's avatar
Don Gagne committed
201
void MockLink::_run500HzTasks(void)
202
{
203
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
204
        _paramRequestListWorker();
205
        _logDownloadWorker();
206 207 208 209 210
    }
}

void MockLink::_loadParams(void)
{
211 212 213 214
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
215
            paramFile.setFileName(":/MockLink/APMArduPlaneMockLink.params");
216
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
217
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
218
        } else {
219
            paramFile.setFileName(":/MockLink/APMArduCopterMockLink.params");
220 221
        }
    } else {
222
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
223 224
    }

225

226 227 228
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
229

230
    QTextStream paramStream(&paramFile);
231

232 233
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
234

235 236 237
        if (line.startsWith("#")) {
            continue;
        }
238

239 240
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
241

242 243 244
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
245

246 247
        QVariant paramValue;
        switch (paramType) {
248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
        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;
273
        }
274

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

277
        _mapParamName2Value[_vehicleComponentId][paramName] = paramValue;
278
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
279 280 281 282 283 284 285
    }
}

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

286 287
    mavlink_msg_heartbeat_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
288
                                    _mavlinkChannel,
289 290 291 292 293 294
                                    &msg,
                                    _vehicleType,        // MAV_TYPE
                                    _firmwareType,      // MAV_AUTOPILOT
                                    _mavBaseMode,        // MAV_MODE
                                    _mavCustomMode,      // custom mode
                                    _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
295

296 297
    respondWithMavlinkMessage(msg);
}
298

Don Gagne's avatar
Don Gagne committed
299 300 301 302
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

303 304
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
305
                                    _mavlinkChannel,
306 307 308 309 310 311 312 313
                                    &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
314 315 316 317

    respondWithMavlinkMessage(msg);
}

318 319 320
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
321

322 323 324 325 326 327
    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
328
void MockLink::_writeBytes(const QByteArray bytes)
329 330 331 332 333 334 335 336
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
337

338 339 340 341 342 343 344 345
        _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);
346

347 348 349 350 351 352 353 354
    // 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;
355

Don Gagne's avatar
Don Gagne committed
356 357
#if 0
        // MockLink not quite ready to handle this correctly yet
358 359 360 361
        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
362
#endif
363 364 365 366 367 368 369 370
    }
}

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

372 373
    for (qint64 i=0; i<cBytes; i++)
    {
374
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
375 376
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
377

378
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
379 380
            continue;
        }
381

382
        switch (msg.msgid) {
383 384 385
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
386

387 388 389
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
390

391 392 393
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
394

395 396 397
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
398

399 400 401
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
402

403 404 405
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
406

407 408 409
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
410

411 412 413
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
414

415 416 417 418 419 420 421 422
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

423 424
        default:
            break;
425 426 427 428 429 430 431
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
432
    qCDebug(MockLinkLog) << "Heartbeat";
433 434 435 436 437 438
}

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

440
    Q_ASSERT(request.target_system == _vehicleSystemId);
441

442 443 444 445
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
446 447 448 449 450 451 452 453
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;
}

454
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
455 456
{
    mavlink_param_union_t   valueUnion;
457

458 459
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
460
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
461

462
    valueUnion.param_float = paramFloat;
463

464
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
465

466
    QVariant paramVariant;
467

468
    switch (paramType) {
469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500
    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;
501
    }
502

503
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
504
    _mapParamName2Value[componentId][paramName] = paramVariant;
505 506
}

507
/// Convert from a parameter variant to the float value from mavlink_param_union_t
508
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
509
{
510
    mavlink_param_union_t   valueUnion;
511

512 513
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
514
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
515

516
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
517
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
518

519
    switch (paramType) {
520
    case MAV_PARAM_TYPE_REAL32:
521
        valueUnion.param_float = paramVar.toFloat();
522
        break;
523

524 525 526 527 528 529 530
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
531

532 533 534 535 536 537 538
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
539

540 541 542 543 544 545 546
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
547

548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
    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;
579
    }
580

581
    return valueUnion.param_float;
582 583 584 585
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
586 587 588 589
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

590
    mavlink_param_request_list_t request;
591

592
    mavlink_msg_param_request_list_decode(&msg, &request);
593

594
    Q_ASSERT(request.target_system == _vehicleSystemId);
595
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
596

Don Gagne's avatar
Don Gagne committed
597 598 599 600
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
601

Don Gagne's avatar
Don Gagne committed
602 603 604 605 606 607 608
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
609

Don Gagne's avatar
Don Gagne committed
610 611 612
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
613

Don Gagne's avatar
Don Gagne committed
614 615 616
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
617

Don Gagne's avatar
Don Gagne committed
618 619
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
620

Don Gagne's avatar
Don Gagne committed
621 622
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
        Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
623

Don Gagne's avatar
Don Gagne committed
624
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
625

Don Gagne's avatar
Don Gagne committed
626 627
        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
628

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

631 632
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
633
                                          _mavlinkChannel,
634 635 636 637 638 639
                                          &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
640
        respondWithMavlinkMessage(responseMsg);
641
    }
dogmaphobic's avatar
dogmaphobic committed
642

Don Gagne's avatar
Don Gagne committed
643 644 645 646 647 648 649 650
    // 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;
651
        }
652 653 654 655 656 657 658
    }
}

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

660
    Q_ASSERT(request.target_system == _vehicleSystemId);
661
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
662

663 664
    // 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
665
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
666
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
667

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

670 671
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
672
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
673

674
    // Save the new value
675
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
676

677 678
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
679 680
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
681
                                      _mavlinkChannel,
682 683 684 685 686 687
                                      &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
688
    respondWithMavlinkMessage(responseMsg);
689 690 691 692
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
693
    mavlink_message_t   responseMsg;
694 695
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
696

Don Gagne's avatar
Don Gagne committed
697
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
698
    int componentId = request.target_component;
699 700

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
701
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
702 703 704 705
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
706 707
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
708
                                          _mavlinkChannel,
709 710 711 712 713 714
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
715 716 717 718
        respondWithMavlinkMessage(responseMsg);
        return;
    }

719
    Q_ASSERT(_mapParamName2Value.contains(componentId));
720

721 722
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
723

724
    Q_ASSERT(request.target_system == _vehicleSystemId);
725

726 727 728
    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);
729
    } else {
730
        // Request is by index
731

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

734
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
735 736
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
737
    }
738

739
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
740
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
741

Don Gagne's avatar
Don Gagne committed
742 743 744 745 746 747
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

748 749
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
750
                                      _mavlinkChannel,
751 752 753 754 755 756
                                      &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
757
    respondWithMavlinkMessage(responseMsg);
758 759
}

760 761 762
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
763

764 765 766 767
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
768

769
    mavlink_message_t responseMsg;
770 771
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
772
                                      _mavlinkChannel,
773 774 775 776
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794
            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
795 796 797 798 799 800 801
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
802
}
803 804 805

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
806 807 808
    static bool firstCmdUser3 = true;
    static bool firstCmdUser4 = true;

809
    mavlink_command_long_t request;
810
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
811

812 813
    mavlink_msg_command_long_decode(&msg, &request);

814 815
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
816 817 818 819 820
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
821
        commandResult = MAV_RESULT_ACCEPTED;
822 823
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
824 825 826
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
827 828 829
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
830 831 832 833
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865
    case MAV_CMD_USER_1:
        // Test command which always returns MAV_RESULT_ACCEPTED
        commandResult = MAV_RESULT_ACCEPTED;
        break;
    case MAV_CMD_USER_2:
        // Test command which always returns MAV_RESULT_FAILED
        commandResult = MAV_RESULT_FAILED;
        break;
    case MAV_CMD_USER_3:
        // Test command which returns MAV_RESULT_ACCEPTED on second attempt
        if (firstCmdUser3) {
           firstCmdUser3 = false;
           return;
        } else {
            firstCmdUser3 = true;
            commandResult = MAV_RESULT_ACCEPTED;
        }
        break;
    case MAV_CMD_USER_4:
        // Test command which returns MAV_RESULT_FAILED on second attempt
        if (firstCmdUser4) {
           firstCmdUser4 = false;
           return;
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
    case MAV_CMD_USER_5:
        // No response
        return;
        break;
866
    }
867 868

    mavlink_message_t commandAck;
869 870
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
871
                                      _mavlinkChannel,
872 873
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
874
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
875 876 877 878
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
879
    respondWithMavlinkMessage(commandAck);
880 881
}

882 883 884 885
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
886 887
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
888
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
889 890
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        flightVersion |= 3 << (8*3);
891
        flightVersion |= 5 << (8*2);
Don Gagne's avatar
Don Gagne committed
892 893 894
        flightVersion |= 0 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
895
#endif
Don Gagne's avatar
Don Gagne committed
896 897 898 899
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
900
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
901
    }
902
#endif
903 904
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
905
                                            _mavlinkChannel,
906
                                            &msg,
907
                                            MAV_PROTOCOL_CAPABILITY_MAVLINK2 | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY),
908 909 910 911 912 913 914 915 916
                                            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,
Don Gagne's avatar
Don Gagne committed
917 918
                                            0,                               // uid
                                            0);                              // uid2
919 920 921
    respondWithMavlinkMessage(msg);
}

922
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
923
{
924
    _missionItemHandler.setMissionItemFailureMode(failureMode);
925
}
926 927 928

void MockLink::_sendHomePosition(void)
{
929 930 931 932 933 934 935 936
    mavlink_message_t msg;

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

937 938
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
939
                                        _mavlinkChannel,
940 941 942 943 944 945
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
946 947
                                        0.0f, 0.0f, 0.0f,
                                        0);
948
    respondWithMavlinkMessage(msg);
949
}
Don Gagne's avatar
Don Gagne committed
950 951 952 953 954 955

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

956 957
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
958
                                      _mavlinkChannel,
959 960 961 962 963 964 965 966 967
                                      &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
968 969 970 971 972 973 974 975
                                      8,                                     // satellite count
                                      //-- Extension
                                      0,                                    // Altitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
                                      0,                                    // Position uncertainty in meters * 1000 (positive for up).
                                      0,                                    // Altitude uncertainty in meters * 1000 (positive for up).
                                      0,                                    // Speed uncertainty in meters * 1000 (positive for up).
                                      0);                                   // Heading / track uncertainty in degrees * 1e5.
        respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
976
}
977

978 979 980 981 982 983 984 985
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
986 987 988 989 990 991 992 993 994 995
    { 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" },
};
996 997 998 999 1000

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

1001 1002
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1003
                                         _mavlinkChannel,
1004 1005 1006
                                         &msg,
                                         status->severity,
                                         status->msg);
1007 1008 1009 1010
        respondWithMavlinkMessage(msg);
    }
}

1011 1012
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1013 1014 1015 1016 1017
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1018 1019 1020 1021 1022 1023 1024
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1025
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1026
    _vehicleType =      source->_vehicleType;
1027
    _sendStatusText =   source->_sendStatusText;
1028
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1029
    _failureMode =      source->_failureMode;
1030 1031 1032 1033 1034 1035
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
1036 1037 1038 1039 1040 1041 1042

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

    _firmwareType =     usource->_firmwareType;
1043
    _vehicleType =      usource->_vehicleType;
1044
    _sendStatusText =   usource->_sendStatusText;
1045
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1046
    _failureMode =      usource->_failureMode;
1047 1048 1049 1050 1051 1052
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1053
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1054
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1055
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1056
    settings.setValue(_failureModeKey, (int)_failureMode);
1057 1058 1059 1060 1061 1062 1063 1064
    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();
1065
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1066
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1067
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1068
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1069 1070 1071 1072 1073 1074 1075 1076 1077
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1078
            qWarning() << "updateSettings not supported";
1079 1080 1081 1082
            //ulink->_restartConnection();
        }
    }
}
1083 1084 1085

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

    mockConfig->setDynamic(true);
1089
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1090

1091
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1092 1093
}

Don Gagne's avatar
Don Gagne committed
1094
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1095 1096 1097 1098 1099 1100
{
    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
1101
    mockConfig->setFailureMode(failureMode);
1102 1103 1104 1105

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1106
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1107 1108 1109 1110 1111 1112
{
    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
1113
    mockConfig->setFailureMode(failureMode);
1114 1115 1116 1117

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1118
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1119 1120 1121 1122 1123 1124
{
    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
1125
    mockConfig->setFailureMode(failureMode);
1126 1127 1128 1129

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1130
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1131 1132 1133 1134 1135 1136
{
    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
1137
    mockConfig->setFailureMode(failureMode);
1138 1139 1140 1141

    return _startMockLink(mockConfig);
}

1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153
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
1154 1155 1156 1157
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1158 1159
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1160
                                      _mavlinkChannel,
1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173
                                      &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
1174 1175 1176 1177

    respondWithMavlinkMessage(msg);

}
1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199

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;
1200 1201
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1202
                                     _mavlinkChannel,
1203 1204 1205
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1206 1207 1208
    respondWithMavlinkMessage(msg);
}

1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220
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;
1221 1222
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1223
                                    _mavlinkChannel,
1224 1225 1226 1227 1228 1229
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1230 1231 1232 1233 1234 1235 1236 1237 1238 1239
    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()) {
1240
        #ifdef UNITTEST_BUILD
1241
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1242
        #endif
1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276
    }

    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;
1277 1278
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1279
                                           _mavlinkChannel,
1280 1281 1282 1283 1284
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

void MockLink::_sendADSBVehicles(void)
{
1299 1300 1301 1302
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

1303 1304 1305 1306 1307
    mavlink_message_t responseMsg;
    mavlink_msg_adsb_vehicle_pack_chan(_vehicleSystemId,
                                       _vehicleComponentId,
                                       _mavlinkChannel,
                                       &responseMsg,
1308 1309 1310
                                       12345,                                       // ICAO address
                                       _adsbVehicleCoordinate.latitude() * 1e7,
                                       _adsbVehicleCoordinate.longitude() * 1e7,
1311
                                       ADSB_ALTITUDE_TYPE_GEOMETRIC,
1312 1313 1314 1315
                                       _adsbVehicleCoordinate.altitude() * 1000,    // Altitude in millimeters
                                       10 * 100,                                    // Heading in centidegress
                                       0, 0,                                        // Horizontal/Vertical velocity
                                       "N1234500",                                  // Callsign
1316
                                       ADSB_EMITTER_TYPE_ROTOCRAFT,
1317
                                       1,                                           // Seconds since last communication
1318
                                       ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_HEADING | ADSB_FLAGS_VALID_CALLSIGN | ADSB_FLAGS_SIMULATED,
1319
                                       0);                                          // Squawk code
1320 1321 1322

    respondWithMavlinkMessage(responseMsg);
}