MockLink.cc 65.2 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
#include "MockLink.h"
11
#include "QGCLoggingCategory.h"
12
#include "QGCApplication.h"
13 14

#ifdef UNITTEST_BUILD
15
#include "UnitTest.h"
16
#endif
17 18 19 20 21 22 23

#include <QTimer>
#include <QDebug>
#include <QFile>

#include <string.h>

24 25
// FIXME: Hack to work around clean headers
#include "FirmwarePlugin/PX4/px4_custom_mode.h"
Daniel Agar's avatar
Daniel Agar committed
26

27
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
Don Gagne's avatar
Don Gagne committed
28
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
29

30 31
// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
// testing of a gazebo vehicle and a mocklink vehicle
32 33 34 35 36 37 38 39 40
#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
41 42
int         MockLink::_nextVehicleSystemId =        128;
const char* MockLink::_failParam =                  "COM_FLTMODE6";
Don Gagne's avatar
Don Gagne committed
43

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

50
MockLink::MockLink(SharedLinkConfigurationPointer& config)
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71
    : 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)
    , _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
72
    , _currentParamRequestListComponentIndex(-1)
73 74 75
    , _currentParamRequestListParamIndex    (-1)
    , _logDownloadCurrentOffset             (0)
    , _logDownloadBytesRemaining            (0)
76
    , _adsbAngle                            (0)
77
{
78 79 80 81
    MockConfiguration* mockConfig = qobject_cast<MockConfiguration*>(_config.data());
    _firmwareType = mockConfig->firmwareType();
    _vehicleType = mockConfig->vehicleType();
    _sendStatusText = mockConfig->sendStatusText();
82
    _highLatency = mockConfig->highLatency();
83
    _failureMode = mockConfig->failureMode();
84

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

87
    union px4_custom_mode   px4_cm;
Don Gagne's avatar
Don Gagne committed
88 89 90 91
    px4_cm.data = 0;
    px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
    _mavCustomMode = px4_cm.data;

92
    _mockLinkFTP = new MockLinkFTP(_vehicleSystemId, _vehicleComponentId, this);
dogmaphobic's avatar
dogmaphobic committed
93

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

96
    _loadParams();
97 98 99

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

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

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

127 128 129
    return true;
}

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

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

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

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

157
    exec();
158

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

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

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

void MockLink::_run10HzTasks(void)
{
196 197 198 199
    if (_highLatency) {
        return;
    }

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

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

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

void MockLink::_loadParams(void)
{
225 226 227 228
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
229
            paramFile.setFileName(":/FirmwarePlugin/APM/Plane.OfflineEditing.params");
230
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
231
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
232 233
        } else if (_vehicleType == MAV_TYPE_GROUND_ROVER ) {
            paramFile.setFileName(":/FirmwarePlugin/APM/Rover.OfflineEditing.params");
234
        } else {
235
            paramFile.setFileName(":/FirmwarePlugin/APM/Copter.OfflineEditing.params");
236 237
        }
    } else {
238
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
239 240
    }

241

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

246
    QTextStream paramStream(&paramFile);
247

248 249
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
250

251 252 253
        if (line.startsWith("#")) {
            continue;
        }
254

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

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

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

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

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

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

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

313 314
    respondWithMavlinkMessage(msg);
}
315

316 317 318 319
void MockLink::_sendHighLatency2(void)
{
    mavlink_message_t   msg;

320 321 322 323
    union px4_custom_mode   px4_cm;
    px4_cm.data = _mavCustomMode;

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

356 357 358 359
void MockLink::_sendSysStatus(void)
{
    mavlink_message_t   msg;
    mavlink_msg_sys_status_pack_chan(
360 361 362 363 364 365 366 367 368 369
                _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
370
                _battery1PctRemaining, // battery_remaining
371
                0,0,0,0,0,0);
372 373 374
    respondWithMavlinkMessage(msg);
}

375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406
void MockLink::_sendBatteryStatus(void)
{
    if(_battery1PctRemaining > 1) {
        _battery1PctRemaining = static_cast<int8_t>(100 - (_runningTime.elapsed() / 1000));
        _battery1TimeRemaining = static_cast<double>(_batteryMaxTimeRemaining) * (static_cast<double>(_battery1PctRemaining) / 100.0);
        if (_battery1PctRemaining > 50) {
            _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
        } else if (_battery1PctRemaining > 30) {
            _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_LOW;
        } else if (_battery1PctRemaining > 20) {
            _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_CRITICAL;
        } else {
            _battery1ChargeState = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
        }
    }
    if(_battery2PctRemaining > 1) {
        _battery2PctRemaining = static_cast<int8_t>(100 - ((_runningTime.elapsed() / 1000) / 2));
        _battery2TimeRemaining = static_cast<double>(_batteryMaxTimeRemaining) * (static_cast<double>(_battery2PctRemaining) / 100.0);
        if (_battery2PctRemaining > 50) {
            _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_OK;
        } else if (_battery2PctRemaining > 30) {
            _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_LOW;
        } else if (_battery2PctRemaining > 20) {
            _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_CRITICAL;
        } else {
            _battery2ChargeState = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
        }
    }

    mavlink_message_t   msg;
    uint16_t            rgVoltages[10];
    uint16_t            rgVoltagesNone[10];
DonLakeFlyer's avatar
DonLakeFlyer committed
407
    uint16_t            rgVoltagesExtNone[4];
408 409 410 411 412 413

    for (int i=0; i<10; i++) {
        rgVoltages[i]       = UINT16_MAX;
        rgVoltagesNone[i]   = UINT16_MAX;
    }
    rgVoltages[0] = rgVoltages[1] = rgVoltages[2] = 4200;
DonLakeFlyer's avatar
DonLakeFlyer committed
414
    memset(rgVoltagesExtNone, 0, sizeof(rgVoltagesExtNone));
415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430

    mavlink_msg_battery_status_pack_chan(
                _vehicleSystemId,
                _vehicleComponentId,
                static_cast<uint8_t>(_mavlinkChannel),
                &msg,
                1,                          // battery id
                MAV_BATTERY_FUNCTION_ALL,
                MAV_BATTERY_TYPE_LIPO,
                2100,                       // temp cdegC
                rgVoltages,
                600,                        // battery cA
                100,                        // current consumed mAh
                -1,                         // energy consumed not supported
                _battery1PctRemaining,
                _battery1TimeRemaining,
DonLakeFlyer's avatar
DonLakeFlyer committed
431 432
                _battery1ChargeState,
                rgVoltagesExtNone);
433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449
    respondWithMavlinkMessage(msg);

    mavlink_msg_battery_status_pack_chan(
                _vehicleSystemId,
                _vehicleComponentId,
                static_cast<uint8_t>(_mavlinkChannel),
                &msg,
                2,                          // battery id
                MAV_BATTERY_FUNCTION_ALL,
                MAV_BATTERY_TYPE_LIPO,
                INT16_MAX,                  // temp cdegC
                rgVoltagesNone,
                600,                        // battery cA
                100,                        // current consumed mAh
                -1,                         // energy consumed not supported
                _battery2PctRemaining,
                _battery2TimeRemaining,
DonLakeFlyer's avatar
DonLakeFlyer committed
450 451
                _battery2ChargeState,
                rgVoltagesExtNone);
452 453 454
    respondWithMavlinkMessage(msg);
}

Don Gagne's avatar
Don Gagne committed
455 456 457 458
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

459 460
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
461
                                    _mavlinkChannel,
462 463 464 465 466 467 468 469
                                    &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
470 471 472 473

    respondWithMavlinkMessage(msg);
}

474 475 476
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
477

478 479 480 481 482 483
    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
484
void MockLink::_writeBytes(const QByteArray bytes)
485 486 487 488 489 490
{
    // This prevents the responses to mavlink messages from being sent until the _writeBytes returns.
    emit writeBytesQueuedSignal(bytes);
}

void MockLink::_writeBytesQueued(const QByteArray bytes)
491 492 493 494 495 496 497 498
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
499

500 501 502 503 504 505 506 507
        _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);
508

509 510 511 512 513 514 515 516
    // 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;
517

Don Gagne's avatar
Don Gagne committed
518 519
#if 0
        // MockLink not quite ready to handle this correctly yet
520 521 522 523
        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
524
#endif
525 526 527 528 529 530 531 532
    }
}

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

534 535
    for (qint64 i=0; i<cBytes; i++)
    {
536
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
537 538
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
539

540
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
541 542
            continue;
        }
543

544
        switch (msg.msgid) {
545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568
        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;
569 570 571 572 573 574
        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
575 576 577
        case MAVLINK_MSG_ID_PARAM_MAP_RC:
            _handleParamMapRC(msg);
            break;
578 579
        default:
            break;
580 581 582 583 584 585 586
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
587
    qCDebug(MockLinkLog) << "Heartbeat";
588 589
}

DoinLakeFlyer's avatar
DoinLakeFlyer committed
590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605
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);
    }
}

606 607 608 609
void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
    mavlink_set_mode_t request;
    mavlink_msg_set_mode_decode(&msg, &request);
610

611
    Q_ASSERT(request.target_system == _vehicleSystemId);
612

613 614 615 616
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
617 618 619 620 621
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
622
    qCDebug(MockLinkLog) << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
Don Gagne's avatar
Don Gagne committed
623 624
}

625
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
626 627
{
    mavlink_param_union_t   valueUnion;
628

629 630
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
631
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
632

633
    valueUnion.param_float = paramFloat;
634

635
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
636

637
    QVariant paramVariant;
638

639
    switch (paramType) {
640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671
    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;
672
    }
673

674
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
675
    _mapParamName2Value[componentId][paramName] = paramVariant;
676 677
}

678
/// Convert from a parameter variant to the float value from mavlink_param_union_t
679
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
680
{
681
    mavlink_param_union_t   valueUnion;
682

683 684
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
685
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
686

687
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
688
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
689

690
    switch (paramType) {
691
    case MAV_PARAM_TYPE_REAL32:
692
        valueUnion.param_float = paramVar.toFloat();
693
        break;
694

695 696 697 698 699 700 701
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
702

703 704 705 706 707 708 709
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
710

711 712 713 714 715 716 717
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
718

719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749
    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;
750
    }
751

752
    return valueUnion.param_float;
753 754 755 756
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
757 758 759 760
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

761
    mavlink_param_request_list_t request;
762

763
    mavlink_msg_param_request_list_decode(&msg, &request);
764

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

Don Gagne's avatar
Don Gagne committed
768 769 770 771
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
772

Don Gagne's avatar
Don Gagne committed
773 774 775 776 777 778 779
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
780

Don Gagne's avatar
Don Gagne committed
781 782 783
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
784

Don Gagne's avatar
Don Gagne committed
785 786 787
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
788

Don Gagne's avatar
Don Gagne committed
789 790
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
791

Don Gagne's avatar
Don Gagne committed
792
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
793
        Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramName));
794

795
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[componentId][paramName];
796

Don Gagne's avatar
Don Gagne committed
797 798
        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
799

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

802 803
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
804
                                          _mavlinkChannel,
805 806 807 808 809 810
                                          &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
811
        respondWithMavlinkMessage(responseMsg);
812
    }
dogmaphobic's avatar
dogmaphobic committed
813

Don Gagne's avatar
Don Gagne committed
814 815 816 817 818 819 820 821
    // 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;
822
        }
823 824 825 826 827 828 829
    }
}

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

831
    Q_ASSERT(request.target_system == _vehicleSystemId);
832
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
833

834 835
    // 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
836
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
837
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
838

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

841
    Q_ASSERT(_mapParamName2Value.contains(componentId));
842
    Q_ASSERT(_mapParamName2MavParamType.contains(componentId));
843
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
844
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[componentId][paramId]);
845

846
    // Save the new value
847
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
848

849 850
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
851 852
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
853
                                      _mavlinkChannel,
854 855 856 857 858 859
                                      &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
860
    respondWithMavlinkMessage(responseMsg);
861 862 863 864
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
865
    mavlink_message_t   responseMsg;
866 867
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
868

DonLakeFlyer's avatar
DonLakeFlyer committed
869
    const QString paramName(QString::fromLocal8Bit(request.param_id, static_cast<int>(strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN))));
870
    int componentId = request.target_component;
871 872

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
873
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
874 875 876 877
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
878 879
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
880
                                          _mavlinkChannel,
881 882 883 884 885 886
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
887 888 889 890
        respondWithMavlinkMessage(responseMsg);
        return;
    }

891
    Q_ASSERT(_mapParamName2Value.contains(componentId));
892

893 894
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
895

896
    Q_ASSERT(request.target_system == _vehicleSystemId);
897

898 899 900
    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);
901
    } else {
902
        // Request is by index
903

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

906
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
907 908
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
909
    }
910

911
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
912
    Q_ASSERT(_mapParamName2MavParamType[componentId].contains(paramId));
913

Don Gagne's avatar
Don Gagne committed
914 915 916 917 918 919
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

920 921
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
922
                                      _mavlinkChannel,
923 924 925
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
926
                                      _mapParamName2MavParamType[componentId][paramId],          // Parameter type
927 928
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
929
    respondWithMavlinkMessage(responseMsg);
930 931
}

932 933 934
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
935

936 937 938 939
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
940

941
    mavlink_message_t responseMsg;
942 943
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
944
                                      _mavlinkChannel,
945 946 947 948
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966
            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
967 968 969 970 971
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
972
    _mockLinkFTP->mavlinkMessageReceived(msg);
973
}
974 975 976

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

980
    bool noAck = false;
981
    mavlink_command_long_t request;
982
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
983

984 985
    mavlink_msg_command_long_decode(&msg, &request);

986 987
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
988 989 990 991 992
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
993
        commandResult = MAV_RESULT_ACCEPTED;
994 995
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
996 997 998
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
999 1000 1001
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
1002 1003 1004 1005
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
1006
    case MAV_CMD_REQUEST_MESSAGE:
1007 1008 1009 1010
        if (_handleRequestMessage(request, noAck)) {
            if (noAck) {
                return;
            }
1011 1012 1013
            commandResult = MAV_RESULT_ACCEPTED;
        }
        break;
1014
    case MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED:
1015 1016 1017
        // Test command which always returns MAV_RESULT_ACCEPTED
        commandResult = MAV_RESULT_ACCEPTED;
        break;
1018
    case MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED:
1019 1020 1021
        // Test command which always returns MAV_RESULT_FAILED
        commandResult = MAV_RESULT_FAILED;
        break;
1022
    case MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED:
1023 1024
        // Test command which returns MAV_RESULT_ACCEPTED on second attempt
        if (firstCmdUser3) {
1025 1026
            firstCmdUser3 = false;
            return;
1027 1028 1029 1030 1031
        } else {
            firstCmdUser3 = true;
            commandResult = MAV_RESULT_ACCEPTED;
        }
        break;
1032
    case MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED:
1033 1034
        // Test command which returns MAV_RESULT_FAILED on second attempt
        if (firstCmdUser4) {
1035 1036
            firstCmdUser4 = false;
            return;
1037 1038 1039 1040 1041
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
1042
    case MAV_CMD_MOCKLINK_NO_RESPONSE:
1043 1044 1045
        // No response
        return;
        break;
1046
    }
1047 1048

    mavlink_message_t commandAck;
1049 1050
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1051
                                      _mavlinkChannel,
1052 1053
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
1054
                                      commandResult,
Gus Grubba's avatar
Gus Grubba committed
1055 1056 1057 1058
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
1059
    respondWithMavlinkMessage(commandAck);
1060 1061
}

1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077
void MockLink::sendUnexpectedCommandAck(MAV_CMD command, MAV_RESULT ackResult)
{
    mavlink_message_t commandAck;
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
                                      _mavlinkChannel,
                                      &commandAck,
                                      command,
                                      ackResult,
                                      0,    // progress
                                      0,    // result_param2
                                      0,    // target_system
                                      0);   // target_component
    respondWithMavlinkMessage(commandAck);
}

1078 1079 1080 1081
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
1082 1083
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
1084
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
1085
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096
        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
1097 1098
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
1099
#endif
Don Gagne's avatar
Don Gagne committed
1100 1101 1102 1103
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
1104
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
1105
    }
1106
#endif
1107 1108
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
1109
                                            _mavlinkChannel,
1110
                                            &msg,
1111
                                            MAV_PROTOCOL_CAPABILITY_MAVLINK2 | MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0),
1112 1113 1114 1115 1116 1117 1118 1119 1120
                                            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
1121 1122
                                            0,                               // uid
                                            0);                              // uid2
1123 1124 1125
    respondWithMavlinkMessage(msg);
}

1126
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, MAV_MISSION_RESULT failureAckResult)
1127
{
1128
    _missionItemHandler.setFailureMode(failureMode, failureAckResult);
1129
}
1130 1131 1132

void MockLink::_sendHomePosition(void)
{
1133 1134 1135 1136 1137 1138 1139 1140
    mavlink_message_t msg;

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

1141 1142
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
1143
                                        _mavlinkChannel,
1144 1145 1146 1147 1148 1149
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
1150 1151
            0.0f, 0.0f, 0.0f,
            0);
1152
    respondWithMavlinkMessage(msg);
1153
}
Don Gagne's avatar
Don Gagne committed
1154 1155 1156 1157 1158 1159

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

1160 1161
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1162
                                      _mavlinkChannel,
1163
                                      &msg,
1164 1165
                                      timeTick++,                           // time since boot
                                      3,                                    // 3D fix
1166 1167 1168
                                      (int32_t)(_vehicleLatitude  * 1E7),
                                      (int32_t)(_vehicleLongitude * 1E7),
                                      (int32_t)(_vehicleAltitude  * 1000),
1169 1170 1171 1172
                                      UINT16_MAX, UINT16_MAX,               // HDOP/VDOP not known
                                      UINT16_MAX,                           // velocity not known
                                      UINT16_MAX,                           // course over ground not known
                                      8,                                    // satellites visible
1173 1174 1175 1176 1177
                                      //-- 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).
1178 1179
                                      0,                                    // Heading / track uncertainty in degrees * 1e5.
                                      65535);                               // Yaw not provided
1180
    respondWithMavlinkMessage(msg);
Don Gagne's avatar
Don Gagne committed
1181
}
1182

1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198 1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220
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);
    }

}

1221 1222 1223 1224 1225 1226 1227 1228
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
1229 1230 1231 1232 1233 1234 1235 1236 1237
    { 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" },
1238
};
1239 1240

    mavlink_message_t msg;
1241 1242 1243 1244

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

1245 1246
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
1247
                                         _mavlinkChannel,
1248 1249
                                         &msg,
                                         status->severity,
1250 1251 1252
                                         status->msg,
                                         0,                     // Not a chunked sequence
                                         0);                    // Not a chunked sequence
1253
        respondWithMavlinkMessage(msg);
1254
    }
1255 1256 1257 1258 1259

    _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
1260 1261
}

1262 1263
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
1264 1265 1266 1267 1268
    , _firmwareType     (MAV_AUTOPILOT_PX4)
    , _vehicleType      (MAV_TYPE_QUADROTOR)
    , _sendStatusText   (false)
    , _highLatency      (false)
    , _failureMode      (FailNone)
1269 1270 1271 1272 1273 1274 1275
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
1276
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1277
    _vehicleType =      source->_vehicleType;
1278
    _sendStatusText =   source->_sendStatusText;
1279
    _highLatency =      source->_highLatency;
Don Gagne's avatar
Don Gagne committed
1280
    _failureMode =      source->_failureMode;
1281 1282 1283 1284 1285
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
1286
    auto* usource = qobject_cast<MockConfiguration*>(source);
1287 1288 1289 1290 1291 1292 1293

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

    _firmwareType =     usource->_firmwareType;
1294
    _vehicleType =      usource->_vehicleType;
1295
    _sendStatusText =   usource->_sendStatusText;
1296
    _highLatency =      usource->_highLatency;
Don Gagne's avatar
Don Gagne committed
1297
    _failureMode =      usource->_failureMode;
1298 1299 1300 1301 1302 1303
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1304
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1305
    settings.setValue(_sendStatusTextKey, _sendStatusText);
1306
    settings.setValue(_highLatencyKey, _highLatency);
Don Gagne's avatar
Don Gagne committed
1307
    settings.setValue(_failureModeKey, (int)_failureMode);
1308 1309 1310 1311 1312 1313 1314 1315
    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();
1316
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1317
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
1318
    _highLatency = settings.value(_highLatencyKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1319
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1320 1321 1322 1323 1324 1325 1326 1327 1328
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1329
            qWarning() << "updateSettings not supported";
1330 1331 1332 1333
            //ulink->_restartConnection();
        }
    }
}
1334 1335 1336

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
1337
    LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
1338 1339

    mockConfig->setDynamic(true);
1340
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1341

1342
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1343 1344
}

1345
MockLink* MockLink::_startMockLinkWorker(QString configName, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1346
{
1347
    MockConfiguration* mockConfig = new MockConfiguration(configName);
1348

1349 1350
    mockConfig->setFirmwareType(firmwareType);
    mockConfig->setVehicleType(vehicleType);
1351
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1352
    mockConfig->setFailureMode(failureMode);
1353 1354 1355 1356

    return _startMockLink(mockConfig);
}

1357
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1358
{
1359 1360
    return _startMockLinkWorker("PX4 MultiRotor MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
}
1361

1362 1363 1364
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("Generic MockLink", MAV_AUTOPILOT_GENERIC, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1365 1366
}

1367 1368 1369 1370 1371
MockLink* MockLink::startNoInitialConnectMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("No Initial Connect MockLink", MAV_AUTOPILOT_PX4, MAV_TYPE_GENERIC, sendStatusText, failureMode);
}

Don Gagne's avatar
Don Gagne committed
1372
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1373
{
1374
    return _startMockLinkWorker("ArduCopter MockLink",MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_QUADROTOR, sendStatusText, failureMode);
1375 1376
}

Don Gagne's avatar
Don Gagne committed
1377
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1378
{
1379
    return _startMockLinkWorker("ArduPlane MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_FIXED_WING, sendStatusText, failureMode);
1380 1381
}

1382 1383
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
1384 1385
    return _startMockLinkWorker("ArduSub MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_SUBMARINE, sendStatusText, failureMode);
}
1386

1387 1388 1389
MockLink*  MockLink::startAPMArduRoverMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    return _startMockLinkWorker("ArduRover MockLink", MAV_AUTOPILOT_ARDUPILOTMEGA, MAV_TYPE_GROUND_ROVER, sendStatusText, failureMode);
1390 1391
}

Don Gagne's avatar
Don Gagne committed
1392 1393 1394 1395
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1396 1397
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1398
                                      _mavlinkChannel,
1399 1400
                                      &msg,
                                      0,                     // time_boot_ms
Don Gagne's avatar
Don Gagne committed
1401 1402 1403 1404
                                      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,
1405
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1406 1407 1408 1409

    respondWithMavlinkMessage(msg);

}
1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431

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;
1432 1433
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1434
                                     _mavlinkChannel,
1435 1436
                                     &msg,
                                     MAV_SEVERITY_INFO,
1437 1438
                                     pCalMessage,
                                     0, 0);                 // Not chunked
1439 1440 1441
    respondWithMavlinkMessage(msg);
}

1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453
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;
1454 1455
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1456
                                    _mavlinkChannel,
1457 1458 1459 1460 1461 1462
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1463 1464 1465 1466 1467 1468 1469 1470 1471 1472
    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()) {
1473
#ifdef UNITTEST_BUILD
1474
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1475
#endif
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
    }

    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;
1510 1511
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1512
                                           _mavlinkChannel,
1513 1514 1515 1516 1517
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

            file.close();
        } else {
            qWarning() << "MockLink::_logDownloadWorker open failed" << file.errorString();
        }
    }
}
1529 1530 1531

void MockLink::_sendADSBVehicles(void)
{
1532 1533 1534 1535
    _adsbAngle += 2;
    _adsbVehicleCoordinate = QGeoCoordinate(_vehicleLatitude, _vehicleLongitude).atDistanceAndAzimuth(500, _adsbAngle);
    _adsbVehicleCoordinate.setAltitude(100);

1536 1537 1538 1539 1540
    mavlink_message_t responseMsg;
    mavlink_msg_adsb_vehicle_pack_chan(_vehicleSystemId,
                                       _vehicleComponentId,
                                       _mavlinkChannel,
                                       &responseMsg,
1541 1542 1543
                                       12345,                                       // ICAO address
                                       _adsbVehicleCoordinate.latitude() * 1e7,
                                       _adsbVehicleCoordinate.longitude() * 1e7,
1544
                                       ADSB_ALTITUDE_TYPE_GEOMETRIC,
1545 1546 1547 1548
                                       _adsbVehicleCoordinate.altitude() * 1000,    // Altitude in millimeters
                                       10 * 100,                                    // Heading in centidegress
                                       0, 0,                                        // Horizontal/Vertical velocity
                                       "N1234500",                                  // Callsign
1549
                                       ADSB_EMITTER_TYPE_ROTOCRAFT,
1550
                                       1,                                           // Seconds since last communication
1551
                                       ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_HEADING | ADSB_FLAGS_VALID_CALLSIGN | ADSB_FLAGS_SIMULATED,
1552
                                       0);                                          // Squawk code
1553 1554 1555

    respondWithMavlinkMessage(responseMsg);
}
1556

1557
bool MockLink::_handleRequestMessage(const mavlink_command_long_t& request, bool& noAck)
1558
{
1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593
    noAck = false;

    switch ((int)request.param1) {
    case MAVLINK_MSG_ID_COMPONENT_INFORMATION:
        switch (static_cast<int>(request.param2)) {
        case COMP_METADATA_TYPE_VERSION:
            _sendVersionMetaData();
            return true;
        case COMP_METADATA_TYPE_PARAMETER:
            _sendParameterMetaData();
            return true;
        }
        break;
    case MAVLINK_MSG_ID_DEBUG:
        switch (_requestMessageFailureMode) {
        case FailRequestMessageNone:
            break;
        case FailRequestMessageCommandAcceptedMsgNotSent:
            return true;
        case FailRequestMessageCommandUnsupported:
            return false;
        case FailRequestMessageCommandNoResponse:
            noAck = true;
            return true;
        case FailRequestMessageCommandAcceptedSecondAttempMsgSent:
            return true;
        }
    {
        mavlink_message_t   responseMsg;
        mavlink_msg_debug_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
                                    _mavlinkChannel,
                                    &responseMsg,
                                    0, 0, 0);
        respondWithMavlinkMessage(responseMsg);
1594 1595 1596 1597 1598 1599 1600 1601 1602 1603
    }
        return true;
    }

    return false;
}

void MockLink::_sendVersionMetaData(void)
{
    mavlink_message_t   responseMsg;
1604
#if 1
1605
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN]       = "mavlinkftp://version.json.gz";
1606 1607 1608
#else
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN]       = "https://bit.ly/31nm0fs";
#endif
1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626
    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;
1627
#if 1
1628
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN]       = "mavlinkftp://parameter.json";
1629 1630 1631
#else
    char                metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN]       = "https://bit.ly/2ZKRIRE";
#endif
1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645
    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);
}