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

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

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

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

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

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

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

97
    _loadParams();
98 99 100

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

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

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

127 128 129
    return true;
}

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

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

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

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

157
    exec();
158

Don Gagne's avatar
Don Gagne committed
159 160 161
    QObject::disconnect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
dogmaphobic's avatar
dogmaphobic committed
162

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

void MockLink::_run1HzTasks(void)
{
168
    if (_mavlinkStarted && _connected) {
169 170
        if (_highLatency) {
            _sendHighLatency2();
171
        } else {
172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187
            _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();
            }
188
        }
189 190 191 192 193
    }
}

void MockLink::_run10HzTasks(void)
{
194 195 196 197
    if (_highLatency) {
        return;
    }

198
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
199
        _sendHeartBeat();
200 201 202 203 204 205
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
206 207 208
    }
}

Don Gagne's avatar
Don Gagne committed
209
void MockLink::_run500HzTasks(void)
210
{
211 212 213 214
    if (_highLatency) {
        return;
    }

215
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
216
        _paramRequestListWorker();
217
        _logDownloadWorker();
218 219 220 221 222
    }
}

void MockLink::_loadParams(void)
{
223 224 225 226
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
227
            paramFile.setFileName(":/MockLink/APMArduPlaneMockLink.params");
228
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
229
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
230
        } else {
231
            paramFile.setFileName(":/MockLink/APMArduCopterMockLink.params");
232 233
        }
    } else {
234
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
235 236
    }

237

238 239 240
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
241

242
    QTextStream paramStream(&paramFile);
243

244 245
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
246

247 248 249
        if (line.startsWith("#")) {
            continue;
        }
250

251 252
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
253

254 255 256
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
257

258 259
        QVariant paramValue;
        switch (paramType) {
260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284
        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;
285
        }
286

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

289
        _mapParamName2Value[_vehicleComponentId][paramName] = paramValue;
290
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
291 292 293 294 295 296 297
    }
}

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

298 299
    mavlink_msg_heartbeat_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
300
                                    _mavlinkChannel,
301 302 303 304 305 306
                                    &msg,
                                    _vehicleType,        // MAV_TYPE
                                    _firmwareType,      // MAV_AUTOPILOT
                                    _mavBaseMode,        // MAV_MODE
                                    _mavCustomMode,      // custom mode
                                    _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
307

308 309
    respondWithMavlinkMessage(msg);
}
310

311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348
void MockLink::_sendHighLatency2(void)
{
    mavlink_message_t   msg;

    mavlink_msg_high_latency2_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
                                        _mavlinkChannel,
                                        &msg,
                                        0,                          // timestamp
                                        _vehicleType,               // MAV_TYPE
                                        _firmwareType,              // MAV_AUTOPILOT
                                        _flightModeEnumValue(),     // flight_mode
                                        (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,                          // failsafe
                                        0, 0, 0);                   // custom0, custom1, custom2

    respondWithMavlinkMessage(msg);
}

Don Gagne's avatar
Don Gagne committed
349 350 351 352
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

353 354
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
355
                                    _mavlinkChannel,
356 357 358 359 360 361 362 363
                                    &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
364 365 366 367

    respondWithMavlinkMessage(msg);
}

368 369 370
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
371

372 373 374 375 376 377
    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
378
void MockLink::_writeBytes(const QByteArray bytes)
379 380 381 382 383 384 385 386
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
387

388 389 390 391 392 393 394 395
        _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);
396

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

Don Gagne's avatar
Don Gagne committed
406 407
#if 0
        // MockLink not quite ready to handle this correctly yet
408 409 410 411
        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
412
#endif
413 414 415 416 417 418 419 420
    }
}

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

422 423
    for (qint64 i=0; i<cBytes; i++)
    {
424
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
425 426
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
427

428
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
429 430
            continue;
        }
431

432
        switch (msg.msgid) {
433 434 435
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
436

437 438 439
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
440

441 442 443
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
444

445 446 447
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
448

449 450 451
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
452

453 454 455
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
456

457 458 459
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
460

461 462 463
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
464

465 466 467 468 469 470 471 472
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

473 474
        default:
            break;
475 476 477 478 479 480 481
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
482
    qCDebug(MockLinkLog) << "Heartbeat";
483 484 485 486 487 488
}

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

490
    Q_ASSERT(request.target_system == _vehicleSystemId);
491

492 493 494 495
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
496 497 498 499 500 501 502 503
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;
}

504
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
505 506
{
    mavlink_param_union_t   valueUnion;
507

508 509
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
510
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
511

512
    valueUnion.param_float = paramFloat;
513

514
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
515

516
    QVariant paramVariant;
517

518
    switch (paramType) {
519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550
    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;
551
    }
552

553
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
554
    _mapParamName2Value[componentId][paramName] = paramVariant;
555 556
}

557
/// Convert from a parameter variant to the float value from mavlink_param_union_t
558
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
559
{
560
    mavlink_param_union_t   valueUnion;
561

562 563
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
564
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
565

566
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
567
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
568

569
    switch (paramType) {
570
    case MAV_PARAM_TYPE_REAL32:
571
        valueUnion.param_float = paramVar.toFloat();
572
        break;
573

574 575 576 577 578 579 580
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
581

582 583 584 585 586 587 588
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
589

590 591 592 593 594 595 596
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
597

598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628
    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;
629
    }
630

631
    return valueUnion.param_float;
632 633 634 635
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
636 637 638 639
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

640
    mavlink_param_request_list_t request;
641

642
    mavlink_msg_param_request_list_decode(&msg, &request);
643

644
    Q_ASSERT(request.target_system == _vehicleSystemId);
645
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
646

Don Gagne's avatar
Don Gagne committed
647 648 649 650
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
651

Don Gagne's avatar
Don Gagne committed
652 653 654 655 656 657 658
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
659

Don Gagne's avatar
Don Gagne committed
660 661 662
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
663

Don Gagne's avatar
Don Gagne committed
664 665 666
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
667

Don Gagne's avatar
Don Gagne committed
668 669
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
670

Don Gagne's avatar
Don Gagne committed
671 672
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
        Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
673

Don Gagne's avatar
Don Gagne committed
674
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
675

Don Gagne's avatar
Don Gagne committed
676 677
        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
678

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

681 682
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
683
                                          _mavlinkChannel,
684 685 686 687 688 689
                                          &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
690
        respondWithMavlinkMessage(responseMsg);
691
    }
dogmaphobic's avatar
dogmaphobic committed
692

Don Gagne's avatar
Don Gagne committed
693 694 695 696 697 698 699 700
    // 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;
701
        }
702 703 704 705 706 707 708
    }
}

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

710
    Q_ASSERT(request.target_system == _vehicleSystemId);
711
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
712

713 714
    // 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
715
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
716
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
717

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

720 721
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
722
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
723

724
    // Save the new value
725
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
726

727 728
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
729 730
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
731
                                      _mavlinkChannel,
732 733 734 735 736 737
                                      &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
738
    respondWithMavlinkMessage(responseMsg);
739 740 741 742
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
743
    mavlink_message_t   responseMsg;
744 745
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
746

Don Gagne's avatar
Don Gagne committed
747
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
748
    int componentId = request.target_component;
749 750

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
751
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
752 753 754 755
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
756 757
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
758
                                          _mavlinkChannel,
759 760 761 762 763 764
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
765 766 767 768
        respondWithMavlinkMessage(responseMsg);
        return;
    }

769
    Q_ASSERT(_mapParamName2Value.contains(componentId));
770

771 772
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
773

774
    Q_ASSERT(request.target_system == _vehicleSystemId);
775

776 777 778
    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);
779
    } else {
780
        // Request is by index
781

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

784
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
785 786
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
787
    }
788

789
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
790
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
791

Don Gagne's avatar
Don Gagne committed
792 793 794 795 796 797
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

798 799
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
800
                                      _mavlinkChannel,
801 802 803 804 805 806
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
                                      _mapParamName2MavParamType[paramId],                       // Parameter type
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
807
    respondWithMavlinkMessage(responseMsg);
808 809
}

810 811 812
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
813

814 815 816 817
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
818

819
    mavlink_message_t responseMsg;
820 821
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
822
                                      _mavlinkChannel,
823 824 825 826
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844
            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
845 846 847 848 849 850 851
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
852
}
853 854 855

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

859
    mavlink_command_long_t request;
860
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
861

862 863
    mavlink_msg_command_long_decode(&msg, &request);

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

    mavlink_message_t commandAck;
919 920
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
921
                                      _mavlinkChannel,
922 923
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
924
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
925 926 927 928
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
929
    respondWithMavlinkMessage(commandAck);
930 931
}

932 933 934 935
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

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

972
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
973
{
974
    _missionItemHandler.setMissionItemFailureMode(failureMode);
975
}
976 977 978

void MockLink::_sendHomePosition(void)
{
979 980 981 982 983 984 985 986
    mavlink_message_t msg;

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

987 988
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
989
                                        _mavlinkChannel,
990 991 992 993 994 995
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
996 997
            0.0f, 0.0f, 0.0f,
            0);
998
    respondWithMavlinkMessage(msg);
999
}
Don Gagne's avatar
Don Gagne committed
1000 1001 1002 1003 1004 1005

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

1006 1007
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1008
                                      _mavlinkChannel,
1009 1010 1011 1012 1013 1014 1015 1016 1017
                                      &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
1018 1019 1020 1021 1022 1023 1024
                                      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.
1025
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1026
}
1027

1028 1029 1030 1031 1032 1033 1034 1035
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1036 1037 1038 1039 1040 1041 1042 1043 1044 1045
    { 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" },
};
1046 1047 1048 1049 1050

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

1051 1052
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1053
                                         _mavlinkChannel,
1054 1055 1056
                                         &msg,
                                         status->severity,
                                         status->msg);
1057 1058 1059 1060
        respondWithMavlinkMessage(msg);
    }
}

1061 1062
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1063 1064 1065 1066 1067
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1068 1069 1070 1071 1072 1073 1074
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1075
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1076
    _vehicleType =      source->_vehicleType;
1077
    _sendStatusText =   source->_sendStatusText;
1078
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1079
    _failureMode =      source->_failureMode;
1080 1081 1082 1083 1084 1085
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
1086 1087 1088 1089 1090 1091 1092

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

    _firmwareType =     usource->_firmwareType;
1093
    _vehicleType =      usource->_vehicleType;
1094
    _sendStatusText =   usource->_sendStatusText;
1095
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1096
    _failureMode =      usource->_failureMode;
1097 1098 1099 1100 1101 1102
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1103
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1104
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1105
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1106
    settings.setValue(_failureModeKey, (int)_failureMode);
1107 1108 1109 1110 1111 1112 1113 1114
    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();
1115
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1116
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1117
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1118
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1119 1120 1121 1122 1123 1124 1125 1126 1127
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1128
            qWarning() << "updateSettings not supported";
1129 1130 1131 1132
            //ulink->_restartConnection();
        }
    }
}
1133 1134 1135

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

    mockConfig->setDynamic(true);
1139
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1140

1141
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1142 1143
}

Don Gagne's avatar
Don Gagne committed
1144
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1145 1146 1147 1148 1149 1150
{
    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
1151
    mockConfig->setFailureMode(failureMode);
1152 1153 1154 1155

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1156
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1157 1158 1159 1160 1161 1162
{
    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
1163
    mockConfig->setFailureMode(failureMode);
1164 1165 1166 1167

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1168
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1169 1170 1171 1172 1173 1174
{
    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
1175
    mockConfig->setFailureMode(failureMode);
1176 1177 1178 1179

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1180
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1181 1182 1183 1184 1185 1186
{
    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
1187
    mockConfig->setFailureMode(failureMode);
1188 1189 1190 1191

    return _startMockLink(mockConfig);
}

1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203
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
1204 1205 1206 1207
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1208 1209
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1210
                                      _mavlinkChannel,
1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223
                                      &msg,
                                      0,                     // time_boot_ms
                                      8,                     // chancount
                                      1500,                  // chan1_raw
                                      1500,                  // chan2_raw
                                      1500,                  // chan3_raw
                                      1500,                  // chan4_raw
                                      1500,                  // chan5_raw
                                      1500,                  // chan6_raw
                                      1500,                  // chan7_raw
                                      1500,                  // chan8_raw
                                      UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1224 1225 1226 1227

    respondWithMavlinkMessage(msg);

}
1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246 1247 1248 1249

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;
1250 1251
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1252
                                     _mavlinkChannel,
1253 1254 1255
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1256 1257 1258
    respondWithMavlinkMessage(msg);
}

1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270
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;
1271 1272
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1273
                                    _mavlinkChannel,
1274 1275 1276 1277 1278 1279
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1280 1281 1282 1283 1284 1285 1286 1287 1288 1289
    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()) {
1290
#ifdef UNITTEST_BUILD
1291
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1292
#endif
1293 1294 1295 1296 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
    }

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

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

void MockLink::_sendADSBVehicles(void)
{
1349 1350 1351 1352
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

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

    respondWithMavlinkMessage(responseMsg);
}
1373 1374 1375 1376 1377

uint8_t MockLink::_flightModeEnumValue(void)
{
    return FLIGHT_MODE_STABILIZED;
}