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

#ifdef UNITTEST_BUILD
16
#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
// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
// testing of a gazebo vehicle and a mocklink vehicle
38 39 40 41 42 43 44 45 46
#if 1
double      MockLink::_defaultVehicleLatitude =     47.397;
double      MockLink::_defaultVehicleLongitude =    8.5455;
double      MockLink::_defaultVehicleAltitude =     488.056;
#else
double      MockLink::_defaultVehicleLatitude =     47.6333022928789;
double      MockLink::_defaultVehicleLongitude =    -122.08833157994995;
double      MockLink::_defaultVehicleAltitude =     19.0;
#endif
47 48
int         MockLink::_nextVehicleSystemId =        128;
const char* MockLink::_failParam =                  "COM_FLTMODE6";
Don Gagne's avatar
Don Gagne committed
49

50
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
51
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
52
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
53
const char* MockConfiguration::_highLatencyKey =    "HighLatency";
Don Gagne's avatar
Don Gagne committed
54
const char* MockConfiguration::_failureModeKey =    "FailureMode";
55

56
MockLink::MockLink(SharedLinkConfigurationPointer& config)
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78
    : 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
79
    , _currentParamRequestListComponentIndex(-1)
80 81 82
    , _currentParamRequestListParamIndex    (-1)
    , _logDownloadCurrentOffset             (0)
    , _logDownloadBytesRemaining            (0)
83
    , _adsbAngle                            (0)
84
{
85 86 87 88
    MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(_config.data());
    _firmwareType = mockConfig->firmwareType();
    _vehicleType = mockConfig->vehicleType();
    _sendStatusText = mockConfig->sendStatusText();
89
    _highLatency = mockConfig->highLatency();
90
    _failureMode = mockConfig->failureMode();
91

Don Gagne's avatar
Don Gagne committed
92 93 94 95 96 97
    union px4_custom_mode   px4_cm;

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

98 99
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
100

101
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
102

103
    _loadParams();
104 105 106

    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(1000, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);
107 108 109 110
}

MockLink::~MockLink(void)
{
111
    _disconnect();
112 113 114
    if (!_logDownloadFilename.isEmpty()) {
        QFile::remove(_logDownloadFilename);
    }
115 116
}

117
bool MockLink::_connect(void)
118
{
119 120
    if (!_connected) {
        _connected = true;
121 122 123 124 125 126 127 128
        _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;
129 130 131
        start();
        emit connected();
    }
132

133 134 135
    return true;
}

Don Gagne's avatar
Don Gagne committed
136
void MockLink::_disconnect(void)
137
{
138
    if (_connected) {
139 140 141
        if (_mavlinkChannel != 0) {
            qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
        }
142
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
143 144
        quit();
        wait();
145 146
        emit disconnected();
    }
147 148 149 150
}

void MockLink::run(void)
{
Don Gagne's avatar
Don Gagne committed
151 152 153
    QTimer  timer1HzTasks;
    QTimer  timer10HzTasks;
    QTimer  timer500HzTasks;
154

Don Gagne's avatar
Don Gagne committed
155 156 157
    QObject::connect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
158

Don Gagne's avatar
Don Gagne committed
159 160 161
    timer1HzTasks.start(1000);
    timer10HzTasks.start(100);
    timer500HzTasks.start(2);
162

163
    exec();
164

Don Gagne's avatar
Don Gagne committed
165 166 167
    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
168

169
    _missionItemHandler.shutdown();
170 171 172 173
}

void MockLink::_run1HzTasks(void)
{
174
    if (_mavlinkStarted && _connected) {
175 176
        if (_highLatency) {
            _sendHighLatency2();
177
        } else {
178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193
            _sendVibration();
            _sendADSBVehicles();
            if (!qgcApp()->runningUnitTests()) {
                // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
                _sendRCChannels();
            }
            if (_sendHomePositionDelayCount > 0) {
                // We delay home position for better testing
                _sendHomePositionDelayCount--;
            } else {
                _sendHomePosition();
            }
            if (_sendStatusText) {
                _sendStatusText = false;
                _sendStatusTextMessages();
            }
194
        }
195 196 197 198 199
    }
}

void MockLink::_run10HzTasks(void)
{
200 201 202 203
    if (_highLatency) {
        return;
    }

204
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
205
        _sendHeartBeat();
206 207 208 209 210 211
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
212 213 214
    }
}

Don Gagne's avatar
Don Gagne committed
215
void MockLink::_run500HzTasks(void)
216
{
217 218 219 220
    if (_highLatency) {
        return;
    }

221
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
222
        _paramRequestListWorker();
223
        _logDownloadWorker();
224 225 226 227 228
    }
}

void MockLink::_loadParams(void)
{
229 230 231 232
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
233
            paramFile.setFileName(":/FirmwarePlugin/APM/Plane.OfflineEditing.params");
234
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
235
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
236 237
        } else if (_vehicleType == MAV_TYPE_GROUND_ROVER ) {
            paramFile.setFileName(":/FirmwarePlugin/APM/Rover.OfflineEditing.params");
238
        } else {
239
            paramFile.setFileName(":/FirmwarePlugin/APM/Copter.OfflineEditing.params");
240 241
        }
    } else {
242
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
243 244
    }

245

246 247 248
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
249

250
    QTextStream paramStream(&paramFile);
251

252 253
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
254

255 256 257
        if (line.startsWith("#")) {
            continue;
        }
258

259 260
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
261

262
        int compId = paramData.at(1).toInt();
263 264 265
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
266

267 268
        QVariant paramValue;
        switch (paramType) {
269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293
        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;
294
        }
295

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

298 299
        _mapParamName2Value[compId][paramName] = paramValue;
        _mapParamName2MavParamType[compId][paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
300 301 302 303 304 305 306
    }
}

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

307 308
    mavlink_msg_heartbeat_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
309
                                    _mavlinkChannel,
310 311 312 313 314 315
                                    &msg,
                                    _vehicleType,        // MAV_TYPE
                                    _firmwareType,      // MAV_AUTOPILOT
                                    _mavBaseMode,        // MAV_MODE
                                    _mavCustomMode,      // custom mode
                                    _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
316

317 318
    respondWithMavlinkMessage(msg);
}
319

320 321 322 323
void MockLink::_sendHighLatency2(void)
{
    mavlink_message_t   msg;

324 325 326 327
    union px4_custom_mode   px4_cm;
    px4_cm.data = _mavCustomMode;

    qDebug() << "Sending" << _mavCustomMode;
328 329 330 331 332 333 334
    mavlink_msg_high_latency2_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
                                        _mavlinkChannel,
                                        &msg,
                                        0,                          // timestamp
                                        _vehicleType,               // MAV_TYPE
                                        _firmwareType,              // MAV_AUTOPILOT
335
                                        px4_cm.custom_mode_hl,      // custom_mode
336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359
                                        (int32_t)(_vehicleLatitude  * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int16_t)_vehicleAltitude,
                                        (int16_t)_vehicleAltitude,  // target_altitude,
                                        0,                          // heading
                                        0,                          // target_heading
                                        0,                          // target_distance
                                        0,                          // throttle
                                        0,                          // airspeed
                                        0,                          // airspeed_sp
                                        0,                          // groundspeed
                                        0,                          // windspeed,
                                        0,                          // wind_heading
                                        UINT8_MAX,                  // eph not known
                                        UINT8_MAX,                  // epv not known
                                        0,                          // temperature_air
                                        0,                          // climb_rate
                                        -1,                         // battery, do not use?
                                        0,                          // wp_num
                                        0,                          // failure_flags
                                        0, 0, 0);                   // custom0, custom1, custom2
    respondWithMavlinkMessage(msg);
}

Don Gagne's avatar
Don Gagne committed
360 361 362 363
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

364 365
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
366
                                    _mavlinkChannel,
367 368 369 370 371 372 373 374
                                    &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
375 376 377 378

    respondWithMavlinkMessage(msg);
}

379 380 381
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
382

383 384 385 386 387 388
    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
389
void MockLink::_writeBytes(const QByteArray bytes)
390 391 392 393 394 395 396 397
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
398

399 400 401 402 403 404 405 406
        _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);
407

408 409 410 411 412 413 414 415
    // 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;
416

Don Gagne's avatar
Don Gagne committed
417 418
#if 0
        // MockLink not quite ready to handle this correctly yet
419 420 421 422
        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
423
#endif
424 425 426 427 428 429 430 431
    }
}

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

433 434
    for (qint64 i=0; i<cBytes; i++)
    {
435
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
436 437
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
438

439
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
440 441
            continue;
        }
442

443
        switch (msg.msgid) {
444 445 446
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
447

448 449 450
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
451

452 453 454
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
455

456 457 458
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
459

460 461 462
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
463

464 465 466
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
467

468 469 470
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
471

472 473 474
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
475

476 477 478 479 480 481 482 483
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

484 485
        default:
            break;
486 487 488 489 490 491 492
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
493
    qCDebug(MockLinkLog) << "Heartbeat";
494 495 496 497 498 499
}

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

501
    Q_ASSERT(request.target_system == _vehicleSystemId);
502

503 504 505 506
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
507 508 509 510 511 512 513 514
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;
}

515
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
516 517
{
    mavlink_param_union_t   valueUnion;
518

519 520
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
521
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
522

523
    valueUnion.param_float = paramFloat;
524

525
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
526

527
    QVariant paramVariant;
528

529
    switch (paramType) {
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 558 559 560 561
    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;
562
    }
563

564
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
565
    _mapParamName2Value[componentId][paramName] = paramVariant;
566 567
}

568
/// Convert from a parameter variant to the float value from mavlink_param_union_t
569
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
570
{
571
    mavlink_param_union_t   valueUnion;
572

573 574
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
575
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
576

577
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
578
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
579

580
    switch (paramType) {
581
    case MAV_PARAM_TYPE_REAL32:
582
        valueUnion.param_float = paramVar.toFloat();
583
        break;
584

585 586 587 588 589 590 591
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
592

593 594 595 596 597 598 599
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
600

601 602 603 604 605 606 607
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
608

609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639
    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;
640
    }
641

642
    return valueUnion.param_float;
643 644 645 646
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
647 648 649 650
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

651
    mavlink_param_request_list_t request;
652

653
    mavlink_msg_param_request_list_decode(&msg, &request);
654

655
    Q_ASSERT(request.target_system == _vehicleSystemId);
656
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
657

Don Gagne's avatar
Don Gagne committed
658 659 660 661
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
662

Don Gagne's avatar
Don Gagne committed
663 664 665 666 667 668 669
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
670

Don Gagne's avatar
Don Gagne committed
671 672 673
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
674

Don Gagne's avatar
Don Gagne committed
675 676 677
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
678

Don Gagne's avatar
Don Gagne committed
679 680
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
681

Don Gagne's avatar
Don Gagne committed
682
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
683
        Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
684

685
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
686

Don Gagne's avatar
Don Gagne committed
687 688
        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
689

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

692 693
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
694
                                          _mavlinkChannel,
695 696 697 698 699 700
                                          &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
701
        respondWithMavlinkMessage(responseMsg);
702
    }
dogmaphobic's avatar
dogmaphobic committed
703

Don Gagne's avatar
Don Gagne committed
704 705 706 707 708 709 710 711
    // 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;
712
        }
713 714 715 716 717 718 719
    }
}

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

721
    Q_ASSERT(request.target_system == _vehicleSystemId);
722
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
723

724 725
    // 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
726
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
727
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
728

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

731
    Q_ASSERT(_mapParamName2Value.contains(componentId));
732
    Q_ASSERT(_mapParamName2MavParamType.contains(componentId));
733
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
734
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[componentId][paramId]);
735

736
    // Save the new value
737
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
738

739 740
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
741 742
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
743
                                      _mavlinkChannel,
744 745 746 747 748 749
                                      &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
750
    respondWithMavlinkMessage(responseMsg);
751 752 753 754
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
755
    mavlink_message_t   responseMsg;
756 757
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
758

Don Gagne's avatar
Don Gagne committed
759
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
760
    int componentId = request.target_component;
761 762

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
763
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
764 765 766 767
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
768 769
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
770
                                          _mavlinkChannel,
771 772 773 774 775 776
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
777 778 779 780
        respondWithMavlinkMessage(responseMsg);
        return;
    }

781
    Q_ASSERT(_mapParamName2Value.contains(componentId));
782

783 784
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
785

786
    Q_ASSERT(request.target_system == _vehicleSystemId);
787

788 789 790
    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);
791
    } else {
792
        // Request is by index
793

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

796
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
797 798
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
799
    }
800

801
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
802
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
803

Don Gagne's avatar
Don Gagne committed
804 805 806 807 808 809
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

810 811
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
812
                                      _mavlinkChannel,
813 814 815
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
816
                                      _mapParamName2MavParamType[componentId][paramId],          // Parameter type
817 818
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
819
    respondWithMavlinkMessage(responseMsg);
820 821
}

822 823 824
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
825

826 827 828 829
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
830

831
    mavlink_message_t responseMsg;
832 833
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
834
                                      _mavlinkChannel,
835 836 837 838
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856
            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
857 858 859 860 861 862 863
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
864
}
865 866 867

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

871
    mavlink_command_long_t request;
872
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
873

874 875
    mavlink_msg_command_long_decode(&msg, &request);

876 877
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
878 879 880 881 882
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
883
        commandResult = MAV_RESULT_ACCEPTED;
884 885
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
886 887 888
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
889 890 891
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
892 893 894 895
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
896 897 898 899 900 901 902 903 904 905 906
    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) {
907 908
            firstCmdUser3 = false;
            return;
909 910 911 912 913 914 915 916
        } 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) {
917 918
            firstCmdUser4 = false;
            return;
919 920 921 922 923 924 925 926 927
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
    case MAV_CMD_USER_5:
        // No response
        return;
        break;
928
    }
929 930

    mavlink_message_t commandAck;
931 932
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
933
                                      _mavlinkChannel,
934 935
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
936
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
937 938 939 940
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
941
    respondWithMavlinkMessage(commandAck);
942 943
}

944 945 946 947
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
948 949
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
950
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
951
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
952 953 954 955 956 957 958 959 960 961 962
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
            flightVersion |= 9 << (8*2);
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
            flightVersion |= 5 << (8*2);
        } else if (_vehicleType == MAV_TYPE_GROUND_ROVER ) {
            flightVersion |= 5 << (8*2);
        } else {
            flightVersion |= 6 << (8*2);
        }
        flightVersion |= 3 << (8*3);    // Major
        flightVersion |= 0 << (8*1);    // Patch
Don Gagne's avatar
Don Gagne committed
963 964
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
965
#endif
Don Gagne's avatar
Don Gagne committed
966 967 968 969
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
970
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
971
    }
972
#endif
973 974
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
975
                                            _mavlinkChannel,
976
                                            &msg,
977
                                            MAV_PROTOCOL_CAPABILITY_MAVLINK2 | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY),
978 979 980 981 982 983 984 985 986
                                            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
987 988
                                            0,                               // uid
                                            0);                              // uid2
989 990 991
    respondWithMavlinkMessage(msg);
}

992
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
993
{
994
    _missionItemHandler.setMissionItemFailureMode(failureMode);
995
}
996 997 998

void MockLink::_sendHomePosition(void)
{
999 1000 1001 1002 1003 1004 1005 1006
    mavlink_message_t msg;

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

1007 1008
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
1009
                                        _mavlinkChannel,
1010 1011 1012 1013 1014 1015
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
1016 1017
            0.0f, 0.0f, 0.0f,
            0);
1018
    respondWithMavlinkMessage(msg);
1019
}
Don Gagne's avatar
Don Gagne committed
1020 1021 1022 1023 1024 1025

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

1026 1027
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1028
                                      _mavlinkChannel,
1029 1030 1031 1032 1033 1034 1035 1036 1037
                                      &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
1038 1039 1040 1041 1042 1043 1044
                                      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.
1045
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1046
}
1047

1048 1049 1050 1051 1052 1053 1054 1055
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1056 1057 1058 1059 1060 1061 1062 1063 1064 1065
    { 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" },
};
1066 1067 1068 1069 1070

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

1071 1072
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1073
                                         _mavlinkChannel,
1074 1075 1076
                                         &msg,
                                         status->severity,
                                         status->msg);
1077
        respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1078 1079 1080 1081 1082 1083 1084 1085

        mavlink_msg_statustext_long_pack_chan(_vehicleSystemId,
                                              _vehicleComponentId,
                                              _mavlinkChannel,
                                              &msg,
                                              status->severity,
                                              status->msg);
        respondWithMavlinkMessage(msg);
1086 1087 1088
    }
}

1089 1090
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1091 1092 1093 1094 1095
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1096 1097 1098 1099 1100 1101 1102
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1103
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1104
    _vehicleType =      source->_vehicleType;
1105
    _sendStatusText =   source->_sendStatusText;
1106
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1107
    _failureMode =      source->_failureMode;
1108 1109 1110 1111 1112 1113
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
1114 1115 1116 1117 1118 1119 1120

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

    _firmwareType =     usource->_firmwareType;
1121
    _vehicleType =      usource->_vehicleType;
1122
    _sendStatusText =   usource->_sendStatusText;
1123
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1124
    _failureMode =      usource->_failureMode;
1125 1126 1127 1128 1129 1130
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1131
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1132
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1133
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1134
    settings.setValue(_failureModeKey, (int)_failureMode);
1135 1136 1137 1138 1139 1140 1141 1142
    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();
1143
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1144
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1145
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1146
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1147 1148 1149 1150 1151 1152 1153 1154 1155
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1156
            qWarning() << "updateSettings not supported";
1157 1158 1159 1160
            //ulink->_restartConnection();
        }
    }
}
1161 1162 1163

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

    mockConfig->setDynamic(true);
1167
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1168

1169
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1170 1171
}

1172
MockLink* MockLink::_startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1173
{
1174
    MockConfiguration* mockConfig = new MockConfiguration(configName);
1175

1176 1177
    mockConfig->setFirmwareType(firmwareType);
    mockConfig->setVehicleType(vehicleType);
1178
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1179
    mockConfig->setFailureMode(failureMode);
1180 1181 1182 1183

    return _startMockLink(mockConfig);
}

1184
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1185
{
1186 1187
    return _startMockLinkWorker("PX4 MultiRotor MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
1188

1189 1190 1191
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("Generic MockLink", MAV_AUTOPILOT_GENERIC, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1192 1193
}

Don Gagne's avatar
Don Gagne committed
1194
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1195
{
1196
    return _startMockLinkWorker("ArduCopter MockLink",MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1197 1198
}

Don Gagne's avatar
Don Gagne committed
1199
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1200
{
1201
    return _startMockLinkWorker("ArduPlane MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_FIXED_WING, sendStatusText, failureMode);
1202 1203
}

1204 1205
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
1206 1207
    return _startMockLinkWorker("ArduSub MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_SUBMARINE, sendStatusText, failureMode);
}
1208

1209 1210 1211
MockLink*  MockLink::startAPMArduRoverMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("ArduRover MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_GROUND_ROVER, sendStatusText, failureMode);
1212 1213
}

Don Gagne's avatar
Don Gagne committed
1214 1215 1216 1217
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1218 1219
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1220
                                      _mavlinkChannel,
1221 1222
                                      &msg,
                                      0,                     // time_boot_ms
Don Gagne's avatar
Don Gagne committed
1223 1224 1225 1226
                                      16,                    // chancount
                                      1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,   // channel 1-8
                                      1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,   // channel 9-16
                                      UINT16_MAX, UINT16_MAX,
1227
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1228 1229 1230 1231

    respondWithMavlinkMessage(msg);

}
1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253

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;
1254 1255
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1256
                                     _mavlinkChannel,
1257 1258 1259
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1260 1261 1262
    respondWithMavlinkMessage(msg);
}

1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274
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;
1275 1276
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1277
                                    _mavlinkChannel,
1278 1279 1280 1281 1282 1283
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1284 1285 1286 1287 1288 1289 1290 1291 1292 1293
    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()) {
1294
#ifdef UNITTEST_BUILD
1295
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1296
#endif
1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330
    }

    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;
1331 1332
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1333
                                           _mavlinkChannel,
1334 1335 1336 1337 1338
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

void MockLink::_sendADSBVehicles(void)
{
1353 1354 1355 1356
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

1357 1358 1359 1360 1361
    mavlink_message_t responseMsg;
    mavlink_msg_adsb_vehicle_pack_chan(_vehicleSystemId,
                                       _vehicleComponentId,
                                       _mavlinkChannel,
                                       &responseMsg,
1362 1363 1364
                                       12345,                                       // ICAO address
                                       _adsbVehicleCoordinate.latitude() * 1e7,
                                       _adsbVehicleCoordinate.longitude() * 1e7,
1365
                                       ADSB_ALTITUDE_TYPE_GEOMETRIC,
1366 1367 1368 1369
                                       _adsbVehicleCoordinate.altitude() * 1000,    // Altitude in millimeters
                                       10 * 100,                                    // Heading in centidegress
                                       0, 0,                                        // Horizontal/Vertical velocity
                                       "N1234500",                                  // Callsign
1370
                                       ADSB_EMITTER_TYPE_ROTOCRAFT,
1371
                                       1,                                           // Seconds since last communication
1372
                                       ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_HEADING | ADSB_FLAGS_VALID_CALLSIGN | ADSB_FLAGS_SIMULATED,
1373
                                       0);                                          // Squawk code
1374 1375 1376

    respondWithMavlinkMessage(responseMsg);
}