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

92
    QObject::connect(this, &MockLink::writeBytesQueuedSignal, this, &MockLink::_writeBytesQueued, Qt::QueuedConnection);
Don Gagne's avatar
Don Gagne committed
93

94
    union px4_custom_mode   px4_cm;
Don Gagne's avatar
Don Gagne committed
95 96 97 98
    px4_cm.data = 0;
    px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
    _mavCustomMode = px4_cm.data;

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

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

104
    _loadParams();
105 106 107

    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(1000, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);
108
    _runningTime.start();
109 110 111 112
}

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

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

135 136 137
    return true;
}

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

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

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

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

165
    exec();
166

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

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

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

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

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

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

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

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

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

248

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

253
    QTextStream paramStream(&paramFile);
254

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

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

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

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

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

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

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

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

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

320 321
    respondWithMavlinkMessage(msg);
}
322

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

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

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

363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384
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
385 386 387 388
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

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

    respondWithMavlinkMessage(msg);
}

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

408 409 410 411 412 413
    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
414
void MockLink::_writeBytes(const QByteArray bytes)
415 416 417 418 419 420
{
    // This prevents the responses to mavlink messages from being sent until the _writeBytes returns.
    emit writeBytesQueuedSignal(bytes);
}

void MockLink::_writeBytesQueued(const QByteArray bytes)
421 422 423 424 425 426 427 428
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
429

430 431
        _handleIncomingMavlinkBytes((uint8_t *)bytes.constData(), bytes.count());
    }
432

433 434 435 436 437 438
}

/// @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);
439

440 441 442 443 444 445 446 447
    // 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;
448

Don Gagne's avatar
Don Gagne committed
449 450
#if 0
        // MockLink not quite ready to handle this correctly yet
451 452 453 454
        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
455
#endif
456 457 458 459 460 461 462 463
    }
}

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

465 466
    for (qint64 i=0; i<cBytes; i++)
    {
467
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
468 469
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
470

471
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
472 473
            continue;
        }
474

475
        switch (msg.msgid) {
476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
500 501 502 503 504 505
        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
506 507 508
        case MAVLINK_MSG_ID_PARAM_MAP_RC:
            _handleParamMapRC(msg);
            break;
509 510
        default:
            break;
511 512 513 514 515 516 517
        }
    }
}

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

DoinLakeFlyer's avatar
DoinLakeFlyer committed
521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536
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);
    }
}

537 538 539 540
void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
    mavlink_set_mode_t request;
    mavlink_msg_set_mode_decode(&msg, &request);
541

542
    Q_ASSERT(request.target_system == _vehicleSystemId);
543

544 545 546 547
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

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

556
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
557 558
{
    mavlink_param_union_t   valueUnion;
559

560 561
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
562
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
563

564
    valueUnion.param_float = paramFloat;
565

566
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
567

568
    QVariant paramVariant;
569

570
    switch (paramType) {
571 572 573 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
    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;
603
    }
604

605
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
606
    _mapParamName2Value[componentId][paramName] = paramVariant;
607 608
}

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

614 615
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
616
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
617

618
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
619
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
620

621
    switch (paramType) {
622
    case MAV_PARAM_TYPE_REAL32:
623
        valueUnion.param_float = paramVar.toFloat();
624
        break;
625

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

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

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

650 651 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
    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;
681
    }
682

683
    return valueUnion.param_float;
684 685 686 687
}

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

692
    mavlink_param_request_list_t request;
693

694
    mavlink_msg_param_request_list_decode(&msg, &request);
695

696
    Q_ASSERT(request.target_system == _vehicleSystemId);
697
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
698

Don Gagne's avatar
Don Gagne committed
699 700 701 702
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
703

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

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

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

Don Gagne's avatar
Don Gagne committed
720 721
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
722

Don Gagne's avatar
Don Gagne committed
723
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
724
        Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
725

726
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
727

Don Gagne's avatar
Don Gagne committed
728 729
        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
730

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

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

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

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

762
    Q_ASSERT(request.target_system == _vehicleSystemId);
763
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
764

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

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

772
    Q_ASSERT(_mapParamName2Value.contains(componentId));
773
    Q_ASSERT(_mapParamName2MavParamType.contains(componentId));
774
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
775
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[componentId][paramId]);
776

777
    // Save the new value
778
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
779

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

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
796
    mavlink_message_t   responseMsg;
797 798
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
799

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

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

822
    Q_ASSERT(_mapParamName2Value.contains(componentId));
823

824 825
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
826

827
    Q_ASSERT(request.target_system == _vehicleSystemId);
828

829 830 831
    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);
832
    } else {
833
        // Request is by index
834

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

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

842
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
843
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
844

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

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

863 864 865
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
866

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

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

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
905
}
906 907 908

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

912
    mavlink_command_long_t request;
913
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
914

915 916
    mavlink_msg_command_long_decode(&msg, &request);

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

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

990 991 992 993
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

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

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

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

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

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

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

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

}

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

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

    mavlink_message_t msg;
1153 1154 1155 1156

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

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

    _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
1172 1173
}

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

}

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

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

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

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

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

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

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

    mockConfig->setDynamic(true);
1252
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1253

1254
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1255 1256
}

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

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

    return _startMockLink(mockConfig);
}

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

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

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

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

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

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

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

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

    respondWithMavlinkMessage(msg);

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

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

1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360
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;
1361 1362
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1363
                                    _mavlinkChannel,
1364 1365 1366 1367 1368 1369
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1370 1371 1372 1373 1374 1375 1376 1377 1378 1379
    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()) {
1380
#ifdef UNITTEST_BUILD
1381
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1382
#endif
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 1415 1416
    }

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

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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

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

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

    respondWithMavlinkMessage(responseMsg);
}
1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518

bool MockLink::_handleRequestMessage(const mavlink_command_long_t& request)
{
    if (request.param1 != MAVLINK_MSG_ID_COMPONENT_INFORMATION) {
        return false;
    }

    switch (static_cast<int>(request.param2)) {
    case COMP_METADATA_TYPE_VERSION:
        _sendVersionMetaData();
        return true;
    case COMP_METADATA_TYPE_PARAMETER:
        _sendParameterMetaData();
        return true;
    }

    return false;
}

void MockLink::_sendVersionMetaData(void)
{
    mavlink_message_t   responseMsg;
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] =       "mavlinkftp://version.json";
    char                translationURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_TRANSLATION_URI_LEN] = "";

    mavlink_msg_component_information_pack_chan(_vehicleSystemId,
                                                _vehicleComponentId,
                                                _mavlinkChannel,
                                                &responseMsg,
                                                0,                          // time_boot_ms
                                                COMP_METADATA_TYPE_VERSION,
                                                1,                          // comp_metadata_uid
                                                metaDataURI,
                                                0,                          // comp_translation_uid
                                                translationURI);
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_sendParameterMetaData(void)
{
    mavlink_message_t   responseMsg;
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] =       "mavlinkftp://parameter.json";
    char                translationURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_TRANSLATION_URI_LEN] = "";

    mavlink_msg_component_information_pack_chan(_vehicleSystemId,
                                                _vehicleComponentId,
                                                _mavlinkChannel,
                                                &responseMsg,
                                                0,                              // time_boot_ms
                                                COMP_METADATA_TYPE_PARAMETER,
                                                1,                              // comp_metadata_uid
                                                metaDataURI,
                                                0,                              // comp_translation_uid
                                                translationURI);
    respondWithMavlinkMessage(responseMsg);
}