MockLink.cc 53.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
    : 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)
73
    , _fileServer                           (nullptr)
74 75 76 77 78
    , _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
    _runningTime.start();
108 109 110 111
}

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

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

134 135 136
    return true;
}

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

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

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

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

164
    exec();
165

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

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

void MockLink::_run1HzTasks(void)
{
175
    if (_mavlinkStarted && _connected) {
176 177
        if (_highLatency) {
            _sendHighLatency2();
178
        } else {
179
            _sendVibration();
180
            _sendSysStatus();
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195
            _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();
            }
196
        }
197 198 199 200 201
    }
}

void MockLink::_run10HzTasks(void)
{
202 203 204 205
    if (_highLatency) {
        return;
    }

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

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

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

void MockLink::_loadParams(void)
{
231 232 233 234
    QFile paramFile;

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

247

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

252
    QTextStream paramStream(&paramFile);
253

254 255
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
256

257 258 259
        if (line.startsWith("#")) {
            continue;
        }
260

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

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

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

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

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

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

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

319 320
    respondWithMavlinkMessage(msg);
}
321

322 323 324 325
void MockLink::_sendHighLatency2(void)
{
    mavlink_message_t   msg;

326 327 328 329
    union px4_custom_mode   px4_cm;
    px4_cm.data = _mavCustomMode;

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

362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383
void MockLink::_sendSysStatus(void)
{
    if(_batteryRemaining > 50) {
        _batteryRemaining = static_cast<int8_t>(100 - (_runningTime.elapsed() / 1000));
    }
    mavlink_message_t   msg;
    mavlink_msg_sys_status_pack_chan(
        _vehicleSystemId,
        _vehicleComponentId,
        static_cast<uint8_t>(_mavlinkChannel),
        &msg,
        0,          // onboard_control_sensors_present
        0,          // onboard_control_sensors_enabled
        0,          // onboard_control_sensors_health
        250,        // load
        4200 * 4,   // voltage_battery
        8000,       // current_battery
        _batteryRemaining, // battery_remaining
        0,0,0,0,0,0);
    respondWithMavlinkMessage(msg);
}

Don Gagne's avatar
Don Gagne committed
384 385 386 387
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

388 389
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
390
                                    _mavlinkChannel,
391 392 393 394 395 396 397 398
                                    &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
399 400 401 402

    respondWithMavlinkMessage(msg);
}

403 404 405
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
406

407 408 409 410 411 412
    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
413
void MockLink::_writeBytes(const QByteArray bytes)
414 415 416 417 418 419 420 421
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
422

423 424 425 426 427 428 429 430
        _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);
431

432 433 434 435 436 437 438 439
    // 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;
440

Don Gagne's avatar
Don Gagne committed
441 442
#if 0
        // MockLink not quite ready to handle this correctly yet
443 444 445 446
        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
447
#endif
448 449 450 451 452 453 454 455
    }
}

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

457 458
    for (qint64 i=0; i<cBytes; i++)
    {
459
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
460 461
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
462

463
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
464 465
            continue;
        }
466

467
        switch (msg.msgid) {
468 469 470
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
471

472 473 474
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
475

476 477 478
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
479

480 481 482
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
483

484 485 486
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
487

488 489 490
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
491

492 493 494
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
495

496 497 498
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
499

500 501 502 503 504 505 506 507
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

508 509
        default:
            break;
510 511 512 513 514 515 516
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
517
    qCDebug(MockLinkLog) << "Heartbeat";
518 519 520 521 522 523
}

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

525
    Q_ASSERT(request.target_system == _vehicleSystemId);
526

527 528 529 530
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
531 532 533 534 535
void MockLink::_handleManualControl(const mavlink_message_t& msg)
{
    mavlink_manual_control_t manualControl;
    mavlink_msg_manual_control_decode(&msg, &manualControl);

Gus Grubba's avatar
Gus Grubba committed
536
    qCDebug(MockLinkLog) << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
Don Gagne's avatar
Don Gagne committed
537 538
}

539
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
540 541
{
    mavlink_param_union_t   valueUnion;
542

543 544
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
545
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
546

547
    valueUnion.param_float = paramFloat;
548

549
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
550

551
    QVariant paramVariant;
552

553
    switch (paramType) {
554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585
    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;
586
    }
587

588
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
589
    _mapParamName2Value[componentId][paramName] = paramVariant;
590 591
}

592
/// Convert from a parameter variant to the float value from mavlink_param_union_t
593
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
594
{
595
    mavlink_param_union_t   valueUnion;
596

597 598
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
599
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
600

601
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
602
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
603

604
    switch (paramType) {
605
    case MAV_PARAM_TYPE_REAL32:
606
        valueUnion.param_float = paramVar.toFloat();
607
        break;
608

609 610 611 612 613 614 615
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
616

617 618 619 620 621 622 623
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
624

625 626 627 628 629 630 631
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
632

633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663
    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;
664
    }
665

666
    return valueUnion.param_float;
667 668 669 670
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
671 672 673 674
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

675
    mavlink_param_request_list_t request;
676

677
    mavlink_msg_param_request_list_decode(&msg, &request);
678

679
    Q_ASSERT(request.target_system == _vehicleSystemId);
680
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
681

Don Gagne's avatar
Don Gagne committed
682 683 684 685
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
686

Don Gagne's avatar
Don Gagne committed
687 688 689 690 691 692 693
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
694

Don Gagne's avatar
Don Gagne committed
695 696 697
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
698

Don Gagne's avatar
Don Gagne committed
699 700 701
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
702

Don Gagne's avatar
Don Gagne committed
703 704
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
705

Don Gagne's avatar
Don Gagne committed
706
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
707
        Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
708

709
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
710

Don Gagne's avatar
Don Gagne committed
711 712
        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
713

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

716 717
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
718
                                          _mavlinkChannel,
719 720 721 722 723 724
                                          &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
725
        respondWithMavlinkMessage(responseMsg);
726
    }
dogmaphobic's avatar
dogmaphobic committed
727

Don Gagne's avatar
Don Gagne committed
728 729 730 731 732 733 734 735
    // 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;
736
        }
737 738 739 740 741 742 743
    }
}

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

745
    Q_ASSERT(request.target_system == _vehicleSystemId);
746
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
747

748 749
    // 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
750
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
751
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
752

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

755
    Q_ASSERT(_mapParamName2Value.contains(componentId));
756
    Q_ASSERT(_mapParamName2MavParamType.contains(componentId));
757
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
758
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[componentId][paramId]);
759

760
    // Save the new value
761
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
762

763 764
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
765 766
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
767
                                      _mavlinkChannel,
768 769 770 771 772 773
                                      &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
774
    respondWithMavlinkMessage(responseMsg);
775 776 777 778
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
779
    mavlink_message_t   responseMsg;
780 781
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
782

DonLakeFlyer's avatar
DonLakeFlyer committed
783
    const QString paramName(QString::fromLocal8Bit(request.param_id, static_cast<int>(strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN))));
784
    int componentId = request.target_component;
785 786

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
787
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
788 789 790 791
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
792 793
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
794
                                          _mavlinkChannel,
795 796 797 798 799 800
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
801 802 803 804
        respondWithMavlinkMessage(responseMsg);
        return;
    }

805
    Q_ASSERT(_mapParamName2Value.contains(componentId));
806

807 808
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
809

810
    Q_ASSERT(request.target_system == _vehicleSystemId);
811

812 813 814
    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);
815
    } else {
816
        // Request is by index
817

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

820
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
821 822
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
823
    }
824

825
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
826
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
827

Don Gagne's avatar
Don Gagne committed
828 829 830 831 832 833
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

834 835
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
836
                                      _mavlinkChannel,
837 838 839
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
840
                                      _mapParamName2MavParamType[componentId][paramId],          // Parameter type
841 842
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
843
    respondWithMavlinkMessage(responseMsg);
844 845
}

846 847 848
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
849

850 851 852 853
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
854

855
    mavlink_message_t responseMsg;
856 857
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
858
                                      _mavlinkChannel,
859 860 861 862
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880
            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
881 882 883 884 885 886 887
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
888
}
889 890 891

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

895
    mavlink_command_long_t request;
896
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
897

898 899
    mavlink_msg_command_long_decode(&msg, &request);

900 901
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
902 903 904 905 906
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
907
        commandResult = MAV_RESULT_ACCEPTED;
908 909
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
910 911 912
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
913 914 915
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
916 917 918 919
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
920 921 922 923 924 925 926 927 928 929 930
    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) {
931 932
            firstCmdUser3 = false;
            return;
933 934 935 936 937 938 939 940
        } 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) {
941 942
            firstCmdUser4 = false;
            return;
943 944 945 946 947 948 949 950 951
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
    case MAV_CMD_USER_5:
        // No response
        return;
        break;
952
    }
953 954

    mavlink_message_t commandAck;
955 956
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
957
                                      _mavlinkChannel,
958 959
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
960
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
961 962 963 964
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
965
    respondWithMavlinkMessage(commandAck);
966 967
}

968 969 970 971
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
972 973
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
974
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
975
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
976 977 978 979 980 981 982 983 984 985 986
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
            flightVersion |= 9 << (8*2);
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
            flightVersion |= 5 << (8*2);
        } else if (_vehicleType == MAV_TYPE_GROUND_ROVER ) {
            flightVersion |= 5 << (8*2);
        } else {
            flightVersion |= 6 << (8*2);
        }
        flightVersion |= 3 << (8*3);    // Major
        flightVersion |= 0 << (8*1);    // Patch
Don Gagne's avatar
Don Gagne committed
987 988
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
989
#endif
Don Gagne's avatar
Don Gagne committed
990 991 992 993
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
994
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
995
    }
996
#endif
997 998
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
999
                                            _mavlinkChannel,
1000
                                            &msg,
1001
                                            MAV_PROTOCOL_CAPABILITY_MAVLINK2 | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY),
1002 1003 1004 1005 1006 1007 1008 1009 1010
                                            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
1011 1012
                                            0,                               // uid
                                            0);                              // uid2
1013 1014 1015
    respondWithMavlinkMessage(msg);
}

1016
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
1017
{
1018
    _missionItemHandler.setMissionItemFailureMode(failureMode);
1019
}
1020 1021 1022

void MockLink::_sendHomePosition(void)
{
1023 1024 1025 1026 1027 1028 1029 1030
    mavlink_message_t msg;

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

1031 1032
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
1033
                                        _mavlinkChannel,
1034 1035 1036 1037 1038 1039
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
1040 1041
            0.0f, 0.0f, 0.0f,
            0);
1042
    respondWithMavlinkMessage(msg);
1043
}
Don Gagne's avatar
Don Gagne committed
1044 1045 1046 1047 1048 1049

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

1050 1051
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1052
                                      _mavlinkChannel,
1053 1054 1055 1056 1057 1058 1059 1060 1061
                                      &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
1062 1063 1064 1065 1066 1067 1068
                                      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.
1069
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1070
}
1071

1072 1073 1074 1075 1076 1077 1078 1079
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1080 1081 1082 1083 1084 1085 1086 1087 1088 1089
    { 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" },
};
1090 1091 1092 1093 1094

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

1095 1096
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1097
                                         _mavlinkChannel,
1098 1099 1100
                                         &msg,
                                         status->severity,
                                         status->msg);
1101
        respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1102 1103 1104 1105 1106 1107 1108 1109

        mavlink_msg_statustext_long_pack_chan(_vehicleSystemId,
                                              _vehicleComponentId,
                                              _mavlinkChannel,
                                              &msg,
                                              status->severity,
                                              status->msg);
        respondWithMavlinkMessage(msg);
1110 1111 1112
    }
}

1113 1114
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1115 1116 1117 1118 1119
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1120 1121 1122 1123 1124 1125 1126
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1127
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1128
    _vehicleType =      source->_vehicleType;
1129
    _sendStatusText =   source->_sendStatusText;
1130
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1131
    _failureMode =      source->_failureMode;
1132 1133 1134 1135 1136
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
1137
    auto* usource = qobject_cast<MockConfiguration*>(source);
1138 1139 1140 1141 1142 1143 1144

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

    _firmwareType =     usource->_firmwareType;
1145
    _vehicleType =      usource->_vehicleType;
1146
    _sendStatusText =   usource->_sendStatusText;
1147
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1148
    _failureMode =      usource->_failureMode;
1149 1150 1151 1152 1153 1154
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1155
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1156
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1157
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1158
    settings.setValue(_failureModeKey, (int)_failureMode);
1159 1160 1161 1162 1163 1164 1165 1166
    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();
1167
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1168
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1169
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1170
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1171 1172 1173 1174 1175 1176 1177 1178 1179
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1180
            qWarning() << "updateSettings not supported";
1181 1182 1183 1184
            //ulink->_restartConnection();
        }
    }
}
1185 1186 1187

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
1188
    LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
1189 1190

    mockConfig->setDynamic(true);
1191
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1192

1193
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1194 1195
}

1196
MockLink* MockLink::_startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1197
{
1198
    MockConfiguration* mockConfig = new MockConfiguration(configName);
1199

1200 1201
    mockConfig->setFirmwareType(firmwareType);
    mockConfig->setVehicleType(vehicleType);
1202
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1203
    mockConfig->setFailureMode(failureMode);
1204 1205 1206 1207

    return _startMockLink(mockConfig);
}

1208
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1209
{
1210 1211
    return _startMockLinkWorker("PX4 MultiRotor MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
1212

1213 1214 1215
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("Generic MockLink", MAV_AUTOPILOT_GENERIC, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1216 1217
}

Don Gagne's avatar
Don Gagne committed
1218
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1219
{
1220
    return _startMockLinkWorker("ArduCopter MockLink",MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1221 1222
}

Don Gagne's avatar
Don Gagne committed
1223
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1224
{
1225
    return _startMockLinkWorker("ArduPlane MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_FIXED_WING, sendStatusText, failureMode);
1226 1227
}

1228 1229
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
1230 1231
    return _startMockLinkWorker("ArduSub MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_SUBMARINE, sendStatusText, failureMode);
}
1232

1233 1234 1235
MockLink*  MockLink::startAPMArduRoverMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("ArduRover MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_GROUND_ROVER, sendStatusText, failureMode);
1236 1237
}

Don Gagne's avatar
Don Gagne committed
1238 1239 1240 1241
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1242 1243
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1244
                                      _mavlinkChannel,
1245 1246
                                      &msg,
                                      0,                     // time_boot_ms
Don Gagne's avatar
Don Gagne committed
1247 1248 1249 1250
                                      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,
1251
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1252 1253 1254 1255

    respondWithMavlinkMessage(msg);

}
1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274 1275 1276 1277

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;
1278 1279
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1280
                                     _mavlinkChannel,
1281 1282 1283
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1284 1285 1286
    respondWithMavlinkMessage(msg);
}

1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298
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;
1299 1300
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1301
                                    _mavlinkChannel,
1302 1303 1304 1305 1306 1307
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1308 1309 1310 1311 1312 1313 1314 1315 1316 1317
    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()) {
1318
#ifdef UNITTEST_BUILD
1319
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1320
#endif
1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354
    }

    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;
1355 1356
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1357
                                           _mavlinkChannel,
1358 1359 1360 1361 1362
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

void MockLink::_sendADSBVehicles(void)
{
1377 1378 1379 1380
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

1381 1382 1383 1384 1385
    mavlink_message_t responseMsg;
    mavlink_msg_adsb_vehicle_pack_chan(_vehicleSystemId,
                                       _vehicleComponentId,
                                       _mavlinkChannel,
                                       &responseMsg,
1386 1387 1388
                                       12345,                                       // ICAO address
                                       _adsbVehicleCoordinate.latitude() * 1e7,
                                       _adsbVehicleCoordinate.longitude() * 1e7,
1389
                                       ADSB_ALTITUDE_TYPE_GEOMETRIC,
1390 1391 1392 1393
                                       _adsbVehicleCoordinate.altitude() * 1000,    // Altitude in millimeters
                                       10 * 100,                                    // Heading in centidegress
                                       0, 0,                                        // Horizontal/Vertical velocity
                                       "N1234500",                                  // Callsign
1394
                                       ADSB_EMITTER_TYPE_ROTOCRAFT,
1395
                                       1,                                           // Seconds since last communication
1396
                                       ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_HEADING | ADSB_FLAGS_VALID_CALLSIGN | ADSB_FLAGS_SIMULATED,
1397
                                       0);                                          // Squawk code
1398 1399 1400

    respondWithMavlinkMessage(responseMsg);
}