MockLink.cc 45.5 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10 11

#include "MockLink.h"
12
#include "QGCLoggingCategory.h"
13
#include "QGCApplication.h"
14 15 16

#ifdef UNITTEST_BUILD
    #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>

Don Gagne's avatar
Don Gagne committed
36 37 38 39 40
float           MockLink::_vehicleLatitude =        47.633033f;
float           MockLink::_vehicleLongitude =       -122.08794f;
float           MockLink::_vehicleAltitude =        3.5f;
int             MockLink::_nextVehicleSystemId =    128;
const char*     MockLink::_failParam =              "COM_FLTMODE6";
Don Gagne's avatar
Don Gagne committed
41

42
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
43
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
44
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
Don Gagne's avatar
Don Gagne committed
45
const char* MockConfiguration::_failureModeKey =    "FailureMode";
46

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

Don Gagne's avatar
Don Gagne committed
78 79 80 81 82 83
    union px4_custom_mode   px4_cm;

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

84 85
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
86

87
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
88

89 90 91 92 93
    _loadParams();
}

MockLink::~MockLink(void)
{
94
    _disconnect();
95 96 97
    if (!_logDownloadFilename.isEmpty()) {
        QFile::remove(_logDownloadFilename);
    }
98 99
}

100
bool MockLink::_connect(void)
101
{
102 103
    if (!_connected) {
        _connected = true;
104 105 106 107 108 109 110 111
        _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;
112 113 114
        start();
        emit connected();
    }
115

116 117 118
    return true;
}

Don Gagne's avatar
Don Gagne committed
119
void MockLink::_disconnect(void)
120
{
121
    if (_connected) {
122 123 124
        if (_mavlinkChannel != 0) {
            qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
        }
125
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
126 127
        quit();
        wait();
128 129
        emit disconnected();
    }
130 131 132 133
}

void MockLink::run(void)
{
Don Gagne's avatar
Don Gagne committed
134 135 136
    QTimer  timer1HzTasks;
    QTimer  timer10HzTasks;
    QTimer  timer500HzTasks;
137

Don Gagne's avatar
Don Gagne committed
138 139 140
    QObject::connect(&timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&timer500HzTasks, &QTimer::timeout, this, &MockLink::_run500HzTasks);
141

Don Gagne's avatar
Don Gagne committed
142 143 144
    timer1HzTasks.start(1000);
    timer10HzTasks.start(100);
    timer500HzTasks.start(2);
145

146
    exec();
147

Don Gagne's avatar
Don Gagne committed
148 149 150
    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
151

152
    _missionItemHandler.shutdown();
153 154 155 156
}

void MockLink::_run1HzTasks(void)
{
157
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
158
        _sendVibration();
159 160 161 162
        if (!qgcApp()->runningUnitTests()) {
            // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
            _sendRCChannels();
        }
163
        if (_sendHomePositionDelayCount > 0) {
164
            // We delay home position for better testing
165 166 167 168
            _sendHomePositionDelayCount--;
        } else {
            _sendHomePosition();
        }
169 170 171 172
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
173 174 175 176 177
    }
}

void MockLink::_run10HzTasks(void)
{
178
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
179
        _sendHeartBeat();
180 181 182 183 184 185
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
186 187 188
    }
}

Don Gagne's avatar
Don Gagne committed
189
void MockLink::_run500HzTasks(void)
190
{
191
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
192
        _paramRequestListWorker();
193
        _logDownloadWorker();
194 195 196 197 198
    }
}

void MockLink::_loadParams(void)
{
199 200 201 202
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
203
            paramFile.setFileName(":/MockLink/APMArduPlaneMockLink.params");
204
        } else if (_vehicleType == MAV_TYPE_SUBMARINE ) {
205
            paramFile.setFileName(":/MockLink/APMArduSubMockLink.params");
206
        } else {
207
            paramFile.setFileName(":/MockLink/APMArduCopterMockLink.params");
208 209
        }
    } else {
210
        paramFile.setFileName(":/MockLink/PX4MockLink.params");
211 212
    }

213

214 215 216
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
217

218
    QTextStream paramStream(&paramFile);
219

220 221
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
222

223 224 225
        if (line.startsWith("#")) {
            continue;
        }
226

227 228
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
229

230 231 232
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
233

234 235
        QVariant paramValue;
        switch (paramType) {
236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260
        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;
261
        }
262

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

265
        _mapParamName2Value[_vehicleComponentId][paramName] = paramValue;
266
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
267 268 269 270 271 272 273
    }
}

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

274 275
    mavlink_msg_heartbeat_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
276
                                    _mavlinkChannel,
277 278 279 280 281 282
                                    &msg,
                                    _vehicleType,        // MAV_TYPE
                                    _firmwareType,      // MAV_AUTOPILOT
                                    _mavBaseMode,        // MAV_MODE
                                    _mavCustomMode,      // custom mode
                                    _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
283

284 285
    respondWithMavlinkMessage(msg);
}
286

Don Gagne's avatar
Don Gagne committed
287 288 289 290
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

291 292
    mavlink_msg_vibration_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
293
                                    _mavlinkChannel,
294 295 296 297 298 299 300 301
                                    &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
302 303 304 305

    respondWithMavlinkMessage(msg);
}

306 307 308
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
309

310 311 312 313 314 315
    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
316
void MockLink::_writeBytes(const QByteArray bytes)
317 318 319 320 321 322 323 324
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
325

326 327 328 329 330 331 332 333
        _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);
334

335 336 337 338 339 340 341 342
    // 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;
343

Don Gagne's avatar
Don Gagne committed
344 345
#if 0
        // MockLink not quite ready to handle this correctly yet
346 347 348 349
        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
350
#endif
351 352 353 354 355 356 357 358
    }
}

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

360 361
    for (qint64 i=0; i<cBytes; i++)
    {
362
        if (!mavlink_parse_char(_mavlinkChannel, bytes[i], &msg, &comm)) {
363 364
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
365

366
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
367 368
            continue;
        }
369

370
        switch (msg.msgid) {
371 372 373
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
374

375 376 377
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
378

379 380 381
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
382

383 384 385
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
386

387 388 389
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
390

391 392 393
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
394

395 396 397
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
398

399 400 401
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
402

403 404 405 406 407 408 409 410
        case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
            _handleLogRequestList(msg);
            break;

        case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
            _handleLogRequestData(msg);
            break;

411 412
        default:
            break;
413 414 415 416 417 418 419
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
420
    qCDebug(MockLinkLog) << "Heartbeat";
421 422 423 424 425 426
}

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

428
    Q_ASSERT(request.target_system == _vehicleSystemId);
429

430 431 432 433
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
434 435 436 437 438 439 440 441
void MockLink::_handleManualControl(const mavlink_message_t& msg)
{
    mavlink_manual_control_t manualControl;
    mavlink_msg_manual_control_decode(&msg, &manualControl);

    qDebug() << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
}

442
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
443 444
{
    mavlink_param_union_t   valueUnion;
445

446 447
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
448
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
449

450
    valueUnion.param_float = paramFloat;
451

452
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
453

454
    QVariant paramVariant;
455

456
    switch (paramType) {
457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488
    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;
489
    }
490

491
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
492
    _mapParamName2Value[componentId][paramName] = paramVariant;
493 494
}

495
/// Convert from a parameter variant to the float value from mavlink_param_union_t
496
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
497
{
498
    mavlink_param_union_t   valueUnion;
499

500 501
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
502
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
503

504
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
505
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
506

507
    switch (paramType) {
508
    case MAV_PARAM_TYPE_REAL32:
509
        valueUnion.param_float = paramVar.toFloat();
510
        break;
511

512 513 514 515 516 517 518
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
519

520 521 522 523 524 525 526
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
527

528 529 530 531 532 533 534
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
535

536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566
    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;
567
    }
568

569
    return valueUnion.param_float;
570 571 572 573
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
Don Gagne's avatar
Don Gagne committed
574 575 576 577
    if (_failureMode == MockConfiguration::FailParamNoReponseToRequestList) {
        return;
    }

578
    mavlink_param_request_list_t request;
579

580
    mavlink_msg_param_request_list_decode(&msg, &request);
581

582
    Q_ASSERT(request.target_system == _vehicleSystemId);
583
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
584

Don Gagne's avatar
Don Gagne committed
585 586 587 588
    // Start the worker routine
    _currentParamRequestListComponentIndex = 0;
    _currentParamRequestListParamIndex = 0;
}
589

Don Gagne's avatar
Don Gagne committed
590 591 592 593 594 595 596
/// Sends the next parameter to the vehicle
void MockLink::_paramRequestListWorker(void)
{
    if (_currentParamRequestListComponentIndex == -1) {
        // Initial request complete
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
597

Don Gagne's avatar
Don Gagne committed
598 599 600
    int componentId = _mapParamName2Value.keys()[_currentParamRequestListComponentIndex];
    int cParameters = _mapParamName2Value[componentId].count();
    QString paramName = _mapParamName2Value[componentId].keys()[_currentParamRequestListParamIndex];
601

Don Gagne's avatar
Don Gagne committed
602 603 604
    if ((_failureMode == MockConfiguration::FailMissingParamOnInitialReqest || _failureMode == MockConfiguration::FailMissingParamOnAllRequests) && paramName == _failParam) {
        qCDebug(MockLinkLog) << "Skipping param send:" << paramName;
    } else {
605

Don Gagne's avatar
Don Gagne committed
606 607
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t responseMsg;
608

Don Gagne's avatar
Don Gagne committed
609 610
        Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
        Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
611

Don Gagne's avatar
Don Gagne committed
612
        MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
613

Don Gagne's avatar
Don Gagne committed
614 615
        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
616

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

619 620
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,                                   // component id
621
                                          _mavlinkChannel,
622 623 624 625 626 627
                                          &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
628
        respondWithMavlinkMessage(responseMsg);
629
    }
dogmaphobic's avatar
dogmaphobic committed
630

Don Gagne's avatar
Don Gagne committed
631 632 633 634 635 636 637 638
    // 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;
639
        }
640 641 642 643 644 645 646
    }
}

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

648
    Q_ASSERT(request.target_system == _vehicleSystemId);
649
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
650

651 652
    // 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
653
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
654
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
655

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

658 659
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
660
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
661

662
    // Save the new value
663
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
664

665 666
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
667 668
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
669
                                      _mavlinkChannel,
670 671 672 673 674 675
                                      &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
676
    respondWithMavlinkMessage(responseMsg);
677 678 679 680
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
681
    mavlink_message_t   responseMsg;
682 683
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
684

Don Gagne's avatar
Don Gagne committed
685
    const QString paramName(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
686
    int componentId = request.target_component;
687 688

    // special case for magic _HASH_CHECK value
Don Gagne's avatar
Don Gagne committed
689
    if (request.target_component == MAV_COMP_ID_ALL && paramName == "_HASH_CHECK") {
690 691 692 693
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
694 695
        mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                          componentId,
696
                                          _mavlinkChannel,
697 698 699 700 701 702
                                          &responseMsg,
                                          request.param_id,
                                          valueUnion.param_float,
                                          MAV_PARAM_TYPE_UINT32,
                                          0,
                                          -1);
703 704 705 706
        respondWithMavlinkMessage(responseMsg);
        return;
    }

707
    Q_ASSERT(_mapParamName2Value.contains(componentId));
708

709 710
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
711

712
    Q_ASSERT(request.target_system == _vehicleSystemId);
713

714 715 716
    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);
717
    } else {
718
        // Request is by index
719

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

722
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
723 724
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
725
    }
726

727
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
728
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
729

Don Gagne's avatar
Don Gagne committed
730 731 732 733 734 735
    if (_failureMode == MockConfiguration::FailMissingParamOnAllRequests && strcmp(paramId, _failParam) == 0) {
        qCDebug(MockLinkLog) << "Ignoring request read for " << _failParam;
        // Fail to send this param no matter what
        return;
    }

736 737
    mavlink_msg_param_value_pack_chan(_vehicleSystemId,
                                      componentId,                                               // component id
738
                                      _mavlinkChannel,
739 740 741 742 743 744
                                      &responseMsg,                                              // Outgoing message
                                      paramId,                                                   // Parameter name
                                      _floatUnionForParam(componentId, paramId),                 // Parameter value
                                      _mapParamName2MavParamType[paramId],                       // Parameter type
                                      _mapParamName2Value[componentId].count(),                  // Total number of parameters
                                      _mapParamName2Value[componentId].keys().indexOf(paramId)); // Index of this parameter
745
    respondWithMavlinkMessage(responseMsg);
746 747
}

748 749 750
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
751

752 753 754 755
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
756

757
    mavlink_message_t responseMsg;
758 759
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
760
                                      _mavlinkChannel,
761 762 763 764
                                      &responseMsg,          // Outgoing message
                                      0,                     // time since boot, ignored
                                      18,                    // channel count
                                      chanRaw[0],            // channel raw value
765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782
            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
783 784 785 786 787 788 789
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
790
}
791 792 793

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

797
    mavlink_command_long_t request;
798
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
799

800 801
    mavlink_msg_command_long_decode(&msg, &request);

802 803
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
804 805 806 807 808
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
809
        commandResult = MAV_RESULT_ACCEPTED;
810 811
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
812 813 814
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
815 816 817
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
818 819 820 821
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853
    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) {
           firstCmdUser3 = false;
           return;
        } 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) {
           firstCmdUser4 = false;
           return;
        } else {
            firstCmdUser4 = true;
            commandResult = MAV_RESULT_FAILED;
        }
        break;
    case MAV_CMD_USER_5:
        // No response
        return;
        break;
854
    }
855 856

    mavlink_message_t commandAck;
857 858
    mavlink_msg_command_ack_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
859
                                      _mavlinkChannel,
860 861
                                      &commandAck,
                                      request.command,
DonLakeFlyer's avatar
DonLakeFlyer committed
862 863
                                      commandResult,
                                      0);
864
    respondWithMavlinkMessage(commandAck);
865 866
}

867 868 869 870
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

Don Gagne's avatar
Don Gagne committed
871 872 873 874
    uint8_t customVersion[8] = { };
    uint32_t flightVersion = 0;
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        flightVersion |= 3 << (8*3);
875
        flightVersion |= 5 << (8*2);
Don Gagne's avatar
Don Gagne committed
876 877 878 879 880 881 882 883
        flightVersion |= 0 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    } else if (_firmwareType == MAV_AUTOPILOT_PX4) {
        flightVersion |= 1 << (8*3);
        flightVersion |= 4 << (8*2);
        flightVersion |= 1 << (8*1);
        flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
    }
884

885 886
    mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
                                            _vehicleComponentId,
887
                                            _mavlinkChannel,
888 889 890 891 892 893 894 895 896 897 898 899
                                            &msg,
                                            0,                               // capabilities,
                                            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,
                                            0);                              // uid
900 901 902
    respondWithMavlinkMessage(msg);
}

903
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
904
{
905
    _missionItemHandler.setMissionItemFailureMode(failureMode);
906
}
907 908 909

void MockLink::_sendHomePosition(void)
{
910 911 912 913 914 915 916 917
    mavlink_message_t msg;

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

918 919
    mavlink_msg_home_position_pack_chan(_vehicleSystemId,
                                        _vehicleComponentId,
920
                                        _mavlinkChannel,
921 922 923 924 925 926
                                        &msg,
                                        (int32_t)(_vehicleLatitude * 1E7),
                                        (int32_t)(_vehicleLongitude * 1E7),
                                        (int32_t)(_vehicleAltitude * 1000),
                                        0.0f, 0.0f, 0.0f,
                                        &bogus[0],
927 928
                                        0.0f, 0.0f, 0.0f,
                                        0);
929
    respondWithMavlinkMessage(msg);
930
}
Don Gagne's avatar
Don Gagne committed
931 932 933 934 935 936

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

937 938
    mavlink_msg_gps_raw_int_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
939
                                      _mavlinkChannel,
940 941 942 943 944 945 946 947 948 949
                                      &msg,
                                      timeTick++,                            // time since boot
                                      3,                                     // 3D fix
                                      (int32_t)(_vehicleLatitude  * 1E7),
                                      (int32_t)(_vehicleLongitude * 1E7),
                                      (int32_t)(_vehicleAltitude  * 1000),
                                      UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                      UINT16_MAX,                            // velocity not known
                                      UINT16_MAX,                            // course over ground not known
                                      8);                                    // satellite count
Don Gagne's avatar
Don Gagne committed
950 951
    respondWithMavlinkMessage(msg);
}
952

953 954 955 956 957 958 959 960
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
961 962 963 964 965 966 967 968 969 970
    { 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" },
};
971 972 973 974 975

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

976 977
        mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                         _vehicleComponentId,
978
                                         _mavlinkChannel,
979 980 981
                                         &msg,
                                         status->severity,
                                         status->msg);
982 983 984 985
        respondWithMavlinkMessage(msg);
    }
}

986 987 988
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
989
    , _vehicleType(MAV_TYPE_QUADROTOR)
990
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
991
    , _failureMode(FailNone)
992 993 994 995 996 997 998
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
999
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
1000
    _vehicleType =      source->_vehicleType;
1001
    _sendStatusText =   source->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
1002
    _failureMode =      source->_failureMode;
1003 1004 1005 1006 1007 1008
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
1009 1010 1011 1012 1013 1014 1015

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

    _firmwareType =     usource->_firmwareType;
1016
    _vehicleType =      usource->_vehicleType;
1017
    _sendStatusText =   usource->_sendStatusText;
Don Gagne's avatar
Don Gagne committed
1018
    _failureMode =      usource->_failureMode;
1019 1020 1021 1022 1023 1024
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
1025
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
1026
    settings.setValue(_sendStatusTextKey, _sendStatusText);
Don Gagne's avatar
Don Gagne committed
1027
    settings.setValue(_failureModeKey, (int)_failureMode);
1028 1029 1030 1031 1032 1033 1034 1035
    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();
1036
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
1037
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
Don Gagne's avatar
Don Gagne committed
1038
    _failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
1039 1040 1041 1042 1043 1044 1045 1046 1047
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
1048
            qWarning() << "updateSettings not supported";
1049 1050 1051 1052
            //ulink->_restartConnection();
        }
    }
}
1053 1054 1055

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
1056
    LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
1057 1058

    mockConfig->setDynamic(true);
1059
    SharedLinkConfigurationPointer config = linkMgr->addConfiguration(mockConfig);
1060

1061
    return qobject_cast<MockLink*>(linkMgr->createConnectedLink(config));
1062 1063
}

Don Gagne's avatar
Don Gagne committed
1064
MockLink*  MockLink::startPX4MockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1065 1066 1067 1068 1069 1070
{
    MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1071
    mockConfig->setFailureMode(failureMode);
1072 1073 1074 1075

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1076
MockLink*  MockLink::startGenericMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1077 1078 1079 1080 1081 1082
{
    MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1083
    mockConfig->setFailureMode(failureMode);
1084 1085 1086 1087

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1088
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1089 1090 1091 1092 1093 1094
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1095
    mockConfig->setFailureMode(failureMode);
1096 1097 1098 1099

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1100
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
1101 1102 1103 1104 1105 1106
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
1107
    mockConfig->setFailureMode(failureMode);
1108 1109 1110 1111

    return _startMockLink(mockConfig);
}

1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123
MockLink*  MockLink::startAPMArduSubMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduSub MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_SUBMARINE);
    mockConfig->setSendStatusText(sendStatusText);
    mockConfig->setFailureMode(failureMode);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1124 1125 1126 1127
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

1128 1129
    mavlink_msg_rc_channels_pack_chan(_vehicleSystemId,
                                      _vehicleComponentId,
1130
                                      _mavlinkChannel,
1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143
                                      &msg,
                                      0,                     // time_boot_ms
                                      8,                     // chancount
                                      1500,                  // chan1_raw
                                      1500,                  // chan2_raw
                                      1500,                  // chan3_raw
                                      1500,                  // chan4_raw
                                      1500,                  // chan5_raw
                                      1500,                  // chan6_raw
                                      1500,                  // chan7_raw
                                      1500,                  // chan8_raw
                                      UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
                                      0);                    // rssi
Don Gagne's avatar
Don Gagne committed
1144 1145 1146 1147

    respondWithMavlinkMessage(msg);

}
1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169

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;
1170 1171
    mavlink_msg_statustext_pack_chan(_vehicleSystemId,
                                     _vehicleComponentId,
1172
                                     _mavlinkChannel,
1173 1174 1175
                                     &msg,
                                     MAV_SEVERITY_INFO,
                                     pCalMessage);
1176 1177 1178
    respondWithMavlinkMessage(msg);
}

1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190
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;
1191 1192
    mavlink_msg_log_entry_pack_chan(_vehicleSystemId,
                                    _vehicleComponentId,
1193
                                    _mavlinkChannel,
1194 1195 1196 1197 1198 1199
                                    &responseMsg,
                                    _logDownloadLogId,       // log id
                                    1,                       // num_logs
                                    1,                       // last_log_num
                                    0,                       // time_utc
                                    _logDownloadFileSize);   // size
1200 1201 1202 1203 1204 1205 1206 1207 1208 1209
    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()) {
1210
        #ifdef UNITTEST_BUILD
1211
        _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
1212
        #endif
1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227 1228 1229 1230 1231 1232 1233 1234 1235 1236 1237 1238 1239 1240 1241 1242 1243 1244 1245 1246
    }

    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;
1247 1248
            mavlink_msg_log_data_pack_chan(_vehicleSystemId,
                                           _vehicleComponentId,
1249
                                           _mavlinkChannel,
1250 1251 1252 1253 1254
                                           &responseMsg,
                                           _logDownloadLogId,
                                           _logDownloadCurrentOffset,
                                           bytesToRead,
                                           &buffer[0]);
1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265
            respondWithMavlinkMessage(responseMsg);

            _logDownloadCurrentOffset += bytesToRead;
            _logDownloadBytesRemaining -= bytesToRead;

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