MockLink.cc 56.5 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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;

DoinLakeFlyer's avatar
DoinLakeFlyer committed
508 509 510 511
        case MAVLINK_MSG_ID_PARAM_MAP_RC:
            _handleParamMapRC(msg);
            break;

512 513
        default:
            break;
514 515 516 517 518 519 520
        }
    }
}

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

DoinLakeFlyer's avatar
DoinLakeFlyer committed
524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539
void MockLink::_handleParamMapRC(const mavlink_message_t& msg)
{
    mavlink_param_map_rc_t paramMapRC;
    mavlink_msg_param_map_rc_decode(&msg, &paramMapRC);

    const QString paramName(QString::fromLocal8Bit(paramMapRC.param_id, static_cast<int>(strnlen(paramMapRC.param_id, MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN))));

    if (paramMapRC.param_index == -1) {
        qDebug() << QStringLiteral("MockLink - PARAM_MAP_RC: param(%1) tuningID(%2) centerValue(%3) scale(%4) min(%5) max(%6)").arg(paramName).arg(paramMapRC.parameter_rc_channel_index).arg(paramMapRC.param_value0).arg(paramMapRC.scale).arg(paramMapRC.param_value_min).arg(paramMapRC.param_value_max);
    } else if (paramMapRC.param_index == -2) {
        qDebug() << QStringLiteral("MockLink - PARAM_MAP_RC: Clear tuningID(%1)").arg(paramMapRC.parameter_rc_channel_index);
    } else {
        qWarning() << QStringLiteral("MockLink - PARAM_MAP_RC: Unsupported param_index(%1)").arg(paramMapRC.param_index);
    }
}

540 541 542 543
void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
    mavlink_set_mode_t request;
    mavlink_msg_set_mode_decode(&msg, &request);
544

545
    Q_ASSERT(request.target_system == _vehicleSystemId);
546

547 548 549 550
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
551 552 553 554 555
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
556
    qCDebug(MockLinkLog) << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
Don Gagne's avatar
Don Gagne committed
557 558
}

559
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
560 561
{
    mavlink_param_union_t   valueUnion;
562

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

567
    valueUnion.param_float = paramFloat;
568

569
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
570

571
    QVariant paramVariant;
572

573
    switch (paramType) {
574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605
    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;
606
    }
607

608
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
609
    _mapParamName2Value[componentId][paramName] = paramVariant;
610 611
}

612
/// Convert from a parameter variant to the float value from mavlink_param_union_t
613
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
614
{
615
    mavlink_param_union_t   valueUnion;
616

617 618
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
619
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
620

621
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
622
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
623

624
    switch (paramType) {
625
    case MAV_PARAM_TYPE_REAL32:
626
        valueUnion.param_float = paramVar.toFloat();
627
        break;
628

629 630 631 632 633 634 635
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
636

637 638 639 640 641 642 643
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
644

645 646 647 648 649 650 651
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
652

653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683
    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;
684
    }
685

686
    return valueUnion.param_float;
687 688 689 690
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
691 692 693 694
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

695
    mavlink_param_request_list_t request;
696

697
    mavlink_msg_param_request_list_decode(&msg, &request);
698

699
    Q_ASSERT(request.target_system == _vehicleSystemId);
700
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
701

Don Gagne's avatar
Don Gagne committed
702 703 704 705
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
706

Don Gagne's avatar
Don Gagne committed
707 708 709 710 711 712 713
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
714

Don Gagne's avatar
Don Gagne committed
715 716 717
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
718

Don Gagne's avatar
Don Gagne committed
719 720 721
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
722

Don Gagne's avatar
Don Gagne committed
723 724
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
725

Don Gagne's avatar
Don Gagne committed
726
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
727
        Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
728

729
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
730

Don Gagne's avatar
Don Gagne committed
731 732
        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
733

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

736 737
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
738
                                          _mavlinkChannel,
739 740 741 742 743 744
                                          &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
745
        respondWithMavlinkMessage(responseMsg);
746
    }
dogmaphobic's avatar
dogmaphobic committed
747

Don Gagne's avatar
Don Gagne committed
748 749 750 751 752 753 754 755
    // 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;
756
        }
757 758 759 760 761 762 763
    }
}

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

765
    Q_ASSERT(request.target_system == _vehicleSystemId);
766
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
767

768 769
    // 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
770
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
771
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
772

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

775
    Q_ASSERT(_mapParamName2Value.contains(componentId));
776
    Q_ASSERT(_mapParamName2MavParamType.contains(componentId));
777
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
778
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[componentId][paramId]);
779

780
    // Save the new value
781
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
782

783 784
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
785 786
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
787
                                      _mavlinkChannel,
788 789 790 791 792 793
                                      &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
794
    respondWithMavlinkMessage(responseMsg);
795 796 797 798
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
799
    mavlink_message_t   responseMsg;
800 801
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
802

DonLakeFlyer's avatar
DonLakeFlyer committed
803
    const QString paramName(QString::fromLocal8Bit(request.param_id, static_cast<int>(strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN))));
804
    int componentId = request.target_component;
805 806

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
807
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
808 809 810 811
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
812 813
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
814
                                          _mavlinkChannel,
815 816 817 818 819 820
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
821 822 823 824
        respondWithMavlinkMessage(responseMsg);
        return;
    }

825
    Q_ASSERT(_mapParamName2Value.contains(componentId));
826

827 828
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
829

830
    Q_ASSERT(request.target_system == _vehicleSystemId);
831

832 833 834
    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);
835
    } else {
836
        // Request is by index
837

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

840
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
841 842
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
843
    }
844

845
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
846
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
847

Don Gagne's avatar
Don Gagne committed
848 849 850 851 852 853
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

854 855
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
856
                                      _mavlinkChannel,
857 858 859
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
860
                                      _mapParamName2MavParamType[componentId][paramId],          // Parameter type
861 862
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
863
    respondWithMavlinkMessage(responseMsg);
864 865
}

866 867 868
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
869

870 871 872 873
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
874

875
    mavlink_message_t responseMsg;
876 877
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
878
                                      _mavlinkChannel,
879 880 881 882
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900
            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
901 902 903 904 905 906 907
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
908
}
909 910 911

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

915
    mavlink_command_long_t request;
916
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
917

918 919
    mavlink_msg_command_long_decode(&msg, &request);

920 921
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
922 923 924 925 926
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
927
        commandResult = MAV_RESULT_ACCEPTED;
928 929
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
930 931 932
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
933 934 935
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
936 937 938 939
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
940 941 942 943 944 945 946 947 948 949 950
    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) {
951 952
            firstCmdUser3 = false;
            return;
953 954 955 956 957 958 959 960
        } 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) {
961 962
            firstCmdUser4 = false;
            return;
963 964 965 966 967 968 969 970 971
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
    case MAV_CMD_USER_5:
        // No response
        return;
        break;
972
    }
973 974

    mavlink_message_t commandAck;
975 976
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
977
                                      _mavlinkChannel,
978 979
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
980
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
981 982 983 984
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
985
    respondWithMavlinkMessage(commandAck);
986 987
}

988 989 990 991
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
992 993
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
994
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
995
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
996 997 998 999 1000 1001 1002 1003 1004 1005 1006
        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
1007 1008
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
1009
#endif
Don Gagne's avatar
Don Gagne committed
1010 1011 1012 1013
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
1014
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
1015
    }
1016
#endif
1017 1018
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
1019
                                            _mavlinkChannel,
1020
                                            &msg,
1021
                                            MAV_PROTOCOL_CAPABILITY_MAVLINK2 | MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0),
1022 1023 1024 1025 1026 1027 1028 1029 1030
                                            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
1031 1032
                                            0,                               // uid
                                            0);                              // uid2
1033 1034 1035
    respondWithMavlinkMessage(msg);
}

1036
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
1037
{
1038
    _missionItemHandler.setFailureMode(failureMode, failureAckResult);
1039
}
1040 1041 1042

void MockLink::_sendHomePosition(void)
{
1043 1044 1045 1046 1047 1048 1049 1050
    mavlink_message_t msg;

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

1051 1052
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
1053
                                        _mavlinkChannel,
1054 1055 1056 1057 1058 1059
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
1060 1061
            0.0f, 0.0f, 0.0f,
            0);
1062
    respondWithMavlinkMessage(msg);
1063
}
Don Gagne's avatar
Don Gagne committed
1064 1065 1066 1067 1068 1069

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

1070 1071
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1072
                                      _mavlinkChannel,
1073
                                      &msg,
1074 1075
                                      timeTick++,                           // time since boot
                                      3,                                    // 3D fix
1076 1077 1078
                                      (int32_t)(_vehicleLatitude  * 1E7),
                                      (int32_t)(_vehicleLongitude * 1E7),
                                      (int32_t)(_vehicleAltitude  * 1000),
1079 1080 1081 1082
                                      UINT16_MAX, UINT16_MAX,               // HDOP/VDOP not known
                                      UINT16_MAX,                           // velocity not known
                                      UINT16_MAX,                           // course over ground not known
                                      8,                                    // satellites visible
1083 1084 1085 1086 1087
                                      //-- 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).
1088 1089
                                      0,                                    // Heading / track uncertainty in degrees * 1e5.
                                      65535);                               // Yaw not provided
1090
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1091
}
1092

1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130
void MockLink::_sendChunkedStatusText(uint16_t chunkId, bool missingChunks)
{
    mavlink_message_t msg;

    int cChunks = 4;
    int num = 0;
    for (int i=0; i<cChunks; i++) {
        if (missingChunks && (i & 1)) {
            continue;
        }
        int cBuf = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
        char msgBuf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
        memset(msgBuf, 0, sizeof(msgBuf));
        if (i == cChunks - 1) {
            // Last chunk is partial
            cBuf /= 2;
        }
        for (int j=0; j<cBuf-1; j++) {
            msgBuf[j] = '0' + num++;
            if (num > 9) {
                num = 0;
            }
        }
        msgBuf[cBuf-1] = 'A' + i;

        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
                                         _mavlinkChannel,
                                         &msg,
                                         MAV_SEVERITY_INFO,
                                         msgBuf,
                                         chunkId,
                                         i);                    // chunk sequence number
        respondWithMavlinkMessage(msg);
    }

}

1131 1132 1133 1134 1135 1136 1137 1138
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1139 1140 1141 1142 1143 1144 1145 1146 1147
    { 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" },
1148 1149 1150
    };

    mavlink_message_t msg;
1151 1152 1153 1154

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

1155 1156
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1157
                                         _mavlinkChannel,
1158 1159
                                         &msg,
                                         status->severity,
1160 1161 1162 1163
                                         status->msg,
                                         0,                     // Not a chunked sequence
                                         0);                    // Not a chunked sequence
        //respondWithMavlinkMessage(msg);
1164
    }
1165 1166 1167 1168 1169

    _sendChunkedStatusText(1, false /* missingChunks */);
    _sendChunkedStatusText(2, true /* missingChunks */);
    _sendChunkedStatusText(3, false /* missingChunks */);   // This should cause the previous incomplete chunk to spit out
    _sendChunkedStatusText(4, true /* missingChunks */);    // This should cause the timeout to fire
1170 1171
}

1172 1173
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1174 1175 1176 1177 1178
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1179 1180 1181 1182 1183 1184 1185
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1186
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1187
    _vehicleType =      source->_vehicleType;
1188
    _sendStatusText =   source->_sendStatusText;
1189
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1190
    _failureMode =      source->_failureMode;
1191 1192 1193 1194 1195
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
1196
    auto* usource = qobject_cast<MockConfiguration*>(source);
1197 1198 1199 1200 1201 1202 1203

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

    _firmwareType =     usource->_firmwareType;
1204
    _vehicleType =      usource->_vehicleType;
1205
    _sendStatusText =   usource->_sendStatusText;
1206
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1207
    _failureMode =      usource->_failureMode;
1208 1209 1210 1211 1212 1213
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1214
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1215
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1216
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1217
    settings.setValue(_failureModeKey, (int)_failureMode);
1218 1219 1220 1221 1222 1223 1224 1225
    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();
1226
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1227
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1228
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1229
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1230 1231 1232 1233 1234 1235 1236 1237 1238
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1239
            qWarning() << "updateSettings not supported";
1240 1241 1242 1243
            //ulink->_restartConnection();
        }
    }
}
1244 1245 1246

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
1247
    LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
1248 1249

    mockConfig->setDynamic(true);
1250
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1251

1252
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1253 1254
}

1255
MockLink* MockLink::_startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1256
{
1257
    MockConfiguration* mockConfig = new MockConfiguration(configName);
1258

1259 1260
    mockConfig->setFirmwareType(firmwareType);
    mockConfig->setVehicleType(vehicleType);
1261
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1262
    mockConfig->setFailureMode(failureMode);
1263 1264 1265 1266

    return _startMockLink(mockConfig);
}

1267
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1268
{
1269 1270
    return _startMockLinkWorker("PX4 MultiRotor MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
1271

1272 1273 1274
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("Generic MockLink", MAV_AUTOPILOT_GENERIC, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1275 1276
}

Don Gagne's avatar
Don Gagne committed
1277
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1278
{
1279
    return _startMockLinkWorker("ArduCopter MockLink",MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1280 1281
}

Don Gagne's avatar
Don Gagne committed
1282
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1283
{
1284
    return _startMockLinkWorker("ArduPlane MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_FIXED_WING, sendStatusText, failureMode);
1285 1286
}

1287 1288
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
1289 1290
    return _startMockLinkWorker("ArduSub MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_SUBMARINE, sendStatusText, failureMode);
}
1291

1292 1293 1294
MockLink*  MockLink::startAPMArduRoverMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("ArduRover MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_GROUND_ROVER, sendStatusText, failureMode);
1295 1296
}

Don Gagne's avatar
Don Gagne committed
1297 1298 1299 1300
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1301 1302
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1303
                                      _mavlinkChannel,
1304 1305
                                      &msg,
                                      0,                     // time_boot_ms
Don Gagne's avatar
Don Gagne committed
1306 1307 1308 1309
                                      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,
1310
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1311 1312 1313 1314

    respondWithMavlinkMessage(msg);

}
1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336

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;
1337 1338
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1339
                                     _mavlinkChannel,
1340 1341
                                     &msg,
                                     MAV_SEVERITY_INFO,
1342 1343
                                     pCalMessage,
                                     0, 0);                 // Not chunked
1344 1345 1346
    respondWithMavlinkMessage(msg);
}

1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358
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;
1359 1360
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1361
                                    _mavlinkChannel,
1362 1363 1364 1365 1366 1367
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1368 1369 1370 1371 1372 1373 1374 1375 1376 1377
    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()) {
1378
#ifdef UNITTEST_BUILD
1379
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1380
#endif
1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414
    }

    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;
1415 1416
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1417
                                           _mavlinkChannel,
1418 1419 1420 1421 1422
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

            file.close();
        } else {
            qWarning() << "MockLink::_logDownloadWorker open failed" << file.errorString();
        }
    }
}
1434 1435 1436

void MockLink::_sendADSBVehicles(void)
{
1437 1438 1439 1440
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

1441 1442 1443 1444 1445
    mavlink_message_t responseMsg;
    mavlink_msg_adsb_vehicle_pack_chan(_vehicleSystemId,
                                       _vehicleComponentId,
                                       _mavlinkChannel,
                                       &responseMsg,
1446 1447 1448
                                       12345,                                       // ICAO address
                                       _adsbVehicleCoordinate.latitude() * 1e7,
                                       _adsbVehicleCoordinate.longitude() * 1e7,
1449
                                       ADSB_ALTITUDE_TYPE_GEOMETRIC,
1450 1451 1452 1453
                                       _adsbVehicleCoordinate.altitude() * 1000,    // Altitude in millimeters
                                       10 * 100,                                    // Heading in centidegress
                                       0, 0,                                        // Horizontal/Vertical velocity
                                       "N1234500",                                  // Callsign
1454
                                       ADSB_EMITTER_TYPE_ROTOCRAFT,
1455
                                       1,                                           // Seconds since last communication
1456
                                       ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_HEADING | ADSB_FLAGS_VALID_CALLSIGN | ADSB_FLAGS_SIMULATED,
1457
                                       0);                                          // Squawk code
1458 1459 1460

    respondWithMavlinkMessage(responseMsg);
}