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

#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(":/MockLink/APMArduPlaneMockLink.params");
234
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
235
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
236
        } else {
237
            paramFile.setFileName(":/MockLink/APMArduCopterMockLink.params");
238 239
        }
    } else {
240
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
241 242
    }

243

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

248
    QTextStream paramStream(&paramFile);
249

250 251
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
252

253 254 255
        if (line.startsWith("#")) {
            continue;
        }
256

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

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

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

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

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

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

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

315 316
    respondWithMavlinkMessage(msg);
}
317

318 319 320 321
void MockLink::_sendHighLatency2(void)
{
    mavlink_message_t   msg;

322 323 324 325
    union px4_custom_mode   px4_cm;
    px4_cm.data = _mavCustomMode;

    qDebug() << "Sending" << _mavCustomMode;
326 327 328 329 330 331 332
    mavlink_msg_high_latency2_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
                                        _mavlinkChannel,
                                        &msg,
                                        0,                          // timestamp
                                        _vehicleType,               // MAV_TYPE
                                        _firmwareType,              // MAV_AUTOPILOT
333
                                        px4_cm.custom_mode_hl,      // custom_mode
334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357
                                        (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
358 359 360 361
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

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

    respondWithMavlinkMessage(msg);
}

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

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

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

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

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

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

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

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

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

446 447 448
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
449

450 451 452
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
453

454 455 456
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
457

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

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

466 467 468
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
469

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

474 475 476 477 478 479 480 481
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

482 483
        default:
            break;
484 485 486 487 488 489 490
        }
    }
}

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

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

499
    Q_ASSERT(request.target_system == _vehicleSystemId);
500

501 502 503 504
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

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

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

517 518
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
519
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
520

521
    valueUnion.param_float = paramFloat;
522

523
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
524

525
    QVariant paramVariant;
526

527
    switch (paramType) {
528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559
    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;
560
    }
561

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

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

571 572
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
573
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
574

575
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
576
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
577

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

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

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

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

607 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
    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;
638
    }
639

640
    return valueUnion.param_float;
641 642 643 644
}

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

649
    mavlink_param_request_list_t request;
650

651
    mavlink_msg_param_request_list_decode(&msg, &request);
652

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

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

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

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

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

Don Gagne's avatar
Don Gagne committed
677 678
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
679

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

683
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
684

Don Gagne's avatar
Don Gagne committed
685 686
        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
687

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

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

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

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

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

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

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

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

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

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

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

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

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

779
    Q_ASSERT(_mapParamName2Value.contains(componentId));
780

781 782
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
783

784
    Q_ASSERT(request.target_system == _vehicleSystemId);
785

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

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

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

799
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
800
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
801

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

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

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

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

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

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

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

869
    mavlink_command_long_t request;
870
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
871

872 873
    mavlink_msg_command_long_decode(&msg, &request);

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

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

942 943 944 945
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

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

982
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
983
{
984
    _missionItemHandler.setMissionItemFailureMode(failureMode);
985
}
986 987 988

void MockLink::_sendHomePosition(void)
{
989 990 991 992 993 994 995 996
    mavlink_message_t msg;

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

997 998
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
999
                                        _mavlinkChannel,
1000 1001 1002 1003 1004 1005
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
1006 1007
            0.0f, 0.0f, 0.0f,
            0);
1008
    respondWithMavlinkMessage(msg);
1009
}
Don Gagne's avatar
Don Gagne committed
1010 1011 1012 1013 1014 1015

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

1016 1017
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1018
                                      _mavlinkChannel,
1019 1020 1021 1022 1023 1024 1025 1026 1027
                                      &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
1028 1029 1030 1031 1032 1033 1034
                                      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.
1035
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1036
}
1037

1038 1039 1040 1041 1042 1043 1044 1045
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1046 1047 1048 1049 1050 1051 1052 1053 1054 1055
    { 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" },
};
1056 1057 1058 1059 1060

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

1061 1062
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1063
                                         _mavlinkChannel,
1064 1065 1066
                                         &msg,
                                         status->severity,
                                         status->msg);
1067
        respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1068 1069 1070 1071 1072 1073 1074 1075

        mavlink_msg_statustext_long_pack_chan(_vehicleSystemId,
                                              _vehicleComponentId,
                                              _mavlinkChannel,
                                              &msg,
                                              status->severity,
                                              status->msg);
        respondWithMavlinkMessage(msg);
1076 1077 1078
    }
}

1079 1080
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1081 1082 1083 1084 1085
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1086 1087 1088 1089 1090 1091 1092
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1093
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1094
    _vehicleType =      source->_vehicleType;
1095
    _sendStatusText =   source->_sendStatusText;
1096
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1097
    _failureMode =      source->_failureMode;
1098 1099 1100 1101 1102 1103
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
1104 1105 1106 1107 1108 1109 1110

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

    _firmwareType =     usource->_firmwareType;
1111
    _vehicleType =      usource->_vehicleType;
1112
    _sendStatusText =   usource->_sendStatusText;
1113
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1114
    _failureMode =      usource->_failureMode;
1115 1116 1117 1118 1119 1120
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1121
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1122
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1123
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1124
    settings.setValue(_failureModeKey, (int)_failureMode);
1125 1126 1127 1128 1129 1130 1131 1132
    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();
1133
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1134
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1135
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1136
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1137 1138 1139 1140 1141 1142 1143 1144 1145
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1146
            qWarning() << "updateSettings not supported";
1147 1148 1149 1150
            //ulink->_restartConnection();
        }
    }
}
1151 1152 1153

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

    mockConfig->setDynamic(true);
1157
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1158

1159
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1160 1161
}

Don Gagne's avatar
Don Gagne committed
1162
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1163 1164 1165 1166 1167 1168
{
    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
1169
    mockConfig->setFailureMode(failureMode);
1170 1171 1172 1173

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1174
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1175 1176 1177 1178 1179 1180
{
    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
1181
    mockConfig->setFailureMode(failureMode);
1182 1183 1184 1185

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1186
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1187 1188 1189 1190 1191 1192
{
    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
1193
    mockConfig->setFailureMode(failureMode);
1194 1195 1196 1197

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1198
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1199 1200 1201 1202 1203 1204
{
    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
1205
    mockConfig->setFailureMode(failureMode);
1206 1207 1208 1209

    return _startMockLink(mockConfig);
}

1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221
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
1222 1223 1224 1225
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1226 1227
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1228
                                      _mavlinkChannel,
1229 1230
                                      &msg,
                                      0,                     // time_boot_ms
Don Gagne's avatar
Don Gagne committed
1231 1232 1233 1234
                                      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,
1235
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1236 1237 1238 1239

    respondWithMavlinkMessage(msg);

}
1240 1241 1242 1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259 1260 1261

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;
1262 1263
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1264
                                     _mavlinkChannel,
1265 1266 1267
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1268 1269 1270
    respondWithMavlinkMessage(msg);
}

1271 1272 1273 1274 1275 1276 1277 1278 1279 1280 1281 1282
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;
1283 1284
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1285
                                    _mavlinkChannel,
1286 1287 1288 1289 1290 1291
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1292 1293 1294 1295 1296 1297 1298 1299 1300 1301
    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()) {
1302
#ifdef UNITTEST_BUILD
1303
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1304
#endif
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 1331 1332 1333 1334 1335 1336 1337 1338
    }

    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;
1339 1340
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1341
                                           _mavlinkChannel,
1342 1343 1344 1345 1346
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

void MockLink::_sendADSBVehicles(void)
{
1361 1362 1363 1364
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

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

    respondWithMavlinkMessage(responseMsg);
}