MockLink.cc 37.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 17 18 19 20

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

#include <string.h>

Daniel Agar's avatar
Daniel Agar committed
21 22
#include "px4_custom_mode.h"

23
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
Don Gagne's avatar
Don Gagne committed
24
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
25

26 27 28 29 30
/// @file
///     @brief Mock implementation of a Link.
///
///     @author Don Gagne <don@thegagnes.com>

31 32 33 34
float   MockLink::_vehicleLatitude =        47.633033f;
float   MockLink::_vehicleLongitude =       -122.08794f;
float   MockLink::_vehicleAltitude =        3.5f;
int     MockLink::_nextVehicleSystemId =    128;
Don Gagne's avatar
Don Gagne committed
35

36
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
37
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
38
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
39

40
MockLink::MockLink(MockConfiguration* config)
41
    : _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol())
42 43
    , _name("MockLink")
    , _connected(false)
44 45
    , _vehicleSystemId(_nextVehicleSystemId++)
    , _vehicleComponentId(200)
46
    , _inNSH(false)
Don Gagne's avatar
Don Gagne committed
47
    , _mavlinkStarted(true)
48 49
    , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState(MAV_STATE_STANDBY)
Don Gagne's avatar
Don Gagne committed
50
    , _firmwareType(MAV_AUTOPILOT_PX4)
51
    , _vehicleType(MAV_TYPE_QUADROTOR)
52
    , _fileServer(NULL)
53
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
54
    , _apmSendHomePositionOnEmptyList(false)
55 56
    , _sendHomePositionDelayCount(10)   // No home position for 4 seconds
    , _sendGPSPositionDelayCount(100)   // No gps lock for 5 seconds
57
{
58
    _config = config;
59
    if (_config) {
Don Gagne's avatar
Don Gagne committed
60
        _firmwareType = config->firmwareType();
61
        _vehicleType = config->vehicleType();
62
        _sendStatusText = config->sendStatusText();
Don Gagne's avatar
Don Gagne committed
63
        _config->setLink(this);
64 65
    }

Don Gagne's avatar
Don Gagne committed
66 67 68 69 70 71
    union px4_custom_mode   px4_cm;

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

72 73
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
74

75
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
76

77 78 79 80 81
    _loadParams();
}

MockLink::~MockLink(void)
{
82
    _disconnect();
83 84
}

85
bool MockLink::_connect(void)
86
{
87 88 89 90 91
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
92

93 94 95
    return true;
}

Don Gagne's avatar
Don Gagne committed
96
void MockLink::_disconnect(void)
97
{
98 99
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
100 101
        quit();
        wait();
102 103
        emit disconnected();
    }
104 105 106 107 108 109 110
}

void MockLink::run(void)
{
    QTimer  _timer1HzTasks;
    QTimer  _timer10HzTasks;
    QTimer  _timer50HzTasks;
111

dogmaphobic's avatar
dogmaphobic committed
112
    QObject::connect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
113 114
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
115

116 117 118
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
119

120
    exec();
121

dogmaphobic's avatar
dogmaphobic committed
122
    QObject::disconnect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
123 124
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
dogmaphobic's avatar
dogmaphobic committed
125

126
    _missionItemHandler.shutdown();
127 128 129 130
}

void MockLink::_run1HzTasks(void)
{
131
    if (_mavlinkStarted && _connected) {
132
        _sendHeartBeat();
Don Gagne's avatar
Don Gagne committed
133
        _sendVibration();
134 135 136 137
        if (!qgcApp()->runningUnitTests()) {
            // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
            _sendRCChannels();
        }
138
        if (_sendHomePositionDelayCount > 0) {
139
            // We delay home position for better testing
140 141 142 143
            _sendHomePositionDelayCount--;
        } else {
            _sendHomePosition();
        }
144 145 146 147
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
148 149 150 151 152
    }
}

void MockLink::_run10HzTasks(void)
{
153
    if (_mavlinkStarted && _connected) {
154 155 156 157 158 159
        if (_sendGPSPositionDelayCount > 0) {
            // We delay gps position for better testing
            _sendGPSPositionDelayCount--;
        } else {
            _sendGpsRawInt();
        }
160 161 162 163 164
    }
}

void MockLink::_run50HzTasks(void)
{
165
    if (_mavlinkStarted && _connected) {
166 167 168 169 170
    }
}

void MockLink::_loadParams(void)
{
171 172 173 174 175 176 177 178 179 180 181 182
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
            paramFile.setFileName(":/unittest/APMArduPlaneMockLink.params");
        } else {
            paramFile.setFileName(":/unittest/APMArduCopterMockLink.params");
        }
    } else {
        paramFile.setFileName(":/unittest/PX4MockLink.params");
    }

183

184 185 186
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
187

188
    QTextStream paramStream(&paramFile);
189

190 191
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
192

193 194 195
        if (line.startsWith("#")) {
            continue;
        }
196

197 198
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
199

200
        int componentId = paramData.at(1).toInt();
201 202 203
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
204

205 206
        QVariant paramValue;
        switch (paramType) {
207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231
        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;
232
        }
233

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

236
        _mapParamName2Value[componentId][paramName] = paramValue;
237
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
238 239 240 241 242 243 244 245 246 247
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
Don Gagne's avatar
Don Gagne committed
248
                               _vehicleType,        // MAV_TYPE
Don Gagne's avatar
Don Gagne committed
249
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
250 251
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
252
                               _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
253

254 255
    respondWithMavlinkMessage(msg);
}
256

Don Gagne's avatar
Don Gagne committed
257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

    mavlink_msg_vibration_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &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

    respondWithMavlinkMessage(msg);
}

275 276 277
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
278

279 280 281 282 283 284
    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
285
void MockLink::_writeBytes(const QByteArray bytes)
286 287 288 289 290 291 292 293
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
294

295 296 297 298 299 300 301 302
        _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);
303

304 305 306 307 308 309 310 311
    // 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;
312

Don Gagne's avatar
Don Gagne committed
313 314
#if 0
        // MockLink not quite ready to handle this correctly yet
315 316 317 318
        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
319
#endif
320 321 322 323 324 325 326 327
    }
}

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

329 330
    for (qint64 i=0; i<cBytes; i++)
    {
331
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
332 333
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
334

335
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
336 337
            continue;
        }
338

339
        switch (msg.msgid) {
340 341 342
        case MAVLINK_MSG_ID_HEARTBEAT:
            _handleHeartBeat(msg);
            break;
343

344 345 346
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
            _handleParamRequestList(msg);
            break;
347

348 349 350
        case MAVLINK_MSG_ID_SET_MODE:
            _handleSetMode(msg);
            break;
351

352 353 354
        case MAVLINK_MSG_ID_PARAM_SET:
            _handleParamSet(msg);
            break;
355

356 357 358
        case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
            _handleParamRequestRead(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
359

360 361 362
        case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
            _handleFTP(msg);
            break;
dogmaphobic's avatar
dogmaphobic committed
363

364 365 366
        case MAVLINK_MSG_ID_COMMAND_LONG:
            _handleCommandLong(msg);
            break;
367

368 369 370
        case MAVLINK_MSG_ID_MANUAL_CONTROL:
            _handleManualControl(msg);
            break;
Don Gagne's avatar
Don Gagne committed
371

372 373
        default:
            break;
374 375 376 377 378 379 380
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
381
    qCDebug(MockLinkLog) << "Heartbeat";
382 383 384 385 386 387
}

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

389
    Q_ASSERT(request.target_system == _vehicleSystemId);
390

391 392 393 394
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
395 396 397 398 399 400 401 402
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;
}

403
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
404 405
{
    mavlink_param_union_t   valueUnion;
406

407 408
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
409
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
410

411
    valueUnion.param_float = paramFloat;
412

413
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
414

415
    QVariant paramVariant;
416

417
    switch (paramType) {
418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449
    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;
450
    }
451

452
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
453
    _mapParamName2Value[componentId][paramName] = paramVariant;
454 455
}

456
/// Convert from a parameter variant to the float value from mavlink_param_union_t
457
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
458
{
459
    mavlink_param_union_t   valueUnion;
460

461 462
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
463
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
464

465
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
466
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
467

468
    switch (paramType) {
469
    case MAV_PARAM_TYPE_REAL32:
470
        valueUnion.param_float = paramVar.toFloat();
471
        break;
472

473 474 475 476 477 478 479
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
480

481 482 483 484 485 486 487
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
488

489 490 491 492 493 494 495
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
496

497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527
    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;
528
    }
529

530
    return valueUnion.param_float;
531 532 533 534 535
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
    mavlink_param_request_list_t request;
536

537
    mavlink_msg_param_request_list_decode(&msg, &request);
538

539
    Q_ASSERT(request.target_system == _vehicleSystemId);
540
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
541

542 543
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
544 545

    foreach (int componentId, _mapParamName2Value.keys()) {
546
        uint16_t paramIndex = 0;
547
        int cParameters = _mapParamName2Value[componentId].count();
dogmaphobic's avatar
dogmaphobic committed
548

549
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
550 551 552 553 554 555 556 557 558 559 560
            char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
            mavlink_message_t       responseMsg;

            Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
            Q_ASSERT(_mapParamName2MavParamType.contains(paramName));

            MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];

            Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
            strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);

561
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
562 563 564 565 566 567 568 569 570

            mavlink_msg_param_value_pack(_vehicleSystemId,
                                         componentId,                       // component id
                                         &responseMsg,                      // Outgoing message
                                         paramId,                           // Parameter name
                                         _floatUnionForParam(componentId, paramName),    // Parameter value
                                         paramType,                         // MAV_PARAM_TYPE
                                         cParameters,                       // Total number of parameters
                                         paramIndex++);                     // Index of this parameter
571
            respondWithMavlinkMessage(responseMsg);
dogmaphobic's avatar
dogmaphobic committed
572

573 574 575 576
            // Only first parameter the first time through
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
577

578 579 580 581
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
dogmaphobic's avatar
dogmaphobic committed
582

583
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
584 585
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
586
                skipParam = false;
587 588 589 590
                paramIndex++;
            } else {
                char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
                mavlink_message_t       responseMsg;
dogmaphobic's avatar
dogmaphobic committed
591

592 593
                Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
                Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic's avatar
dogmaphobic committed
594

595
                MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
dogmaphobic's avatar
dogmaphobic committed
596

597 598
                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
599

600
                qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
dogmaphobic's avatar
dogmaphobic committed
601

602 603 604 605 606 607 608 609
                mavlink_msg_param_value_pack(_vehicleSystemId,
                                             componentId,                       // component id
                                             &responseMsg,                      // Outgoing message
                                             paramId,                           // Parameter name
                                             _floatUnionForParam(componentId, paramName),    // Parameter value
                                             paramType,                         // MAV_PARAM_TYPE
                                             cParameters,                       // Total number of parameters
                                             paramIndex++);                     // Index of this parameter
610
                respondWithMavlinkMessage(responseMsg);
611
            }
612
        }
613 614 615 616 617 618 619
    }
}

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

621
    Q_ASSERT(request.target_system == _vehicleSystemId);
622
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
623

624 625
    // 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
626
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
627
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
628

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

631 632
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
633
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
634

635
    // Save the new value
636
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
637

638 639 640
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
641 642 643 644 645 646 647
                                 componentId,                                               // component id
                                 &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
648
    respondWithMavlinkMessage(responseMsg);
649 650 651 652
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
653
    mavlink_message_t   responseMsg;
654 655
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
656 657

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
658
    int componentId = request.target_component;
659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677

    // special case for magic _HASH_CHECK value
    if (request.target_component == MAV_COMP_ID_ALL && param_name == "_HASH_CHECK") {
        mavlink_param_union_t   valueUnion;
        valueUnion.type = MAV_PARAM_TYPE_UINT32;
        valueUnion.param_uint32 = 0;
        // Special case of magic hash check value
        mavlink_msg_param_value_pack(_vehicleSystemId,
                                     componentId,
                                     &responseMsg,
                                     request.param_id,
                                     valueUnion.param_float,
                                     MAV_PARAM_TYPE_UINT32,
                                     0,
                                     -1);
        respondWithMavlinkMessage(responseMsg);
        return;
    }

678
    Q_ASSERT(_mapParamName2Value.contains(componentId));
679

680 681
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
682

683
    Q_ASSERT(request.target_system == _vehicleSystemId);
684

685 686 687
    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);
688
    } else {
689
        // Request is by index
690

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

693
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
694 695
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
696
    }
697

698
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
699
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
700

701
    mavlink_msg_param_value_pack(_vehicleSystemId,
702 703 704 705 706 707 708
                                 componentId,                                               // component id
                                 &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
709
    respondWithMavlinkMessage(responseMsg);
710 711
}

712 713 714
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
715

716 717 718 719
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
720

721 722 723 724 725 726 727
    mavlink_message_t responseMsg;
    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &responseMsg,          // Outgoing message
                                 0,                     // time since boot, ignored
                                 18,                    // channel count
                                 chanRaw[0],            // channel raw value
728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745
            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
746 747 748 749 750 751 752
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
753
}
754 755 756 757

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
    mavlink_command_long_t request;
758
    uint8_t commandResult = MAV_RESULT_UNSUPPORTED;
dogmaphobic's avatar
dogmaphobic committed
759

760 761
    mavlink_msg_command_long_decode(&msg, &request);

762 763
    switch (request.command) {
    case MAV_CMD_COMPONENT_ARM_DISARM:
764 765 766 767 768
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
769
        commandResult = MAV_RESULT_ACCEPTED;
770 771
        break;
    case MAV_CMD_PREFLIGHT_CALIBRATION:
772 773 774
        _handlePreFlightCalibration(request);
        commandResult = MAV_RESULT_ACCEPTED;
        break;
775 776 777
    case MAV_CMD_PREFLIGHT_STORAGE:
        commandResult = MAV_RESULT_ACCEPTED;
        break;
778 779 780 781
    case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
        commandResult = MAV_RESULT_ACCEPTED;
        _respondWithAutopilotVersion();
        break;
782
    }
783 784 785 786 787 788 789 790

    mavlink_message_t commandAck;
    mavlink_msg_command_ack_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &commandAck,
                                 request.command,
                                 commandResult);
    respondWithMavlinkMessage(commandAck);
791 792
}

793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817
void MockLink::_respondWithAutopilotVersion(void)
{
    mavlink_message_t msg;

    uint8_t customVersion[8];
    memset(customVersion, 0, sizeof(customVersion));

    // Only flight_sw_version is supported a this point
    mavlink_msg_autopilot_version_pack(_vehicleSystemId,
                                       _vehicleComponentId,
                                       &msg,
                                       0,                                           // capabilities,
                                       (1 << (8*3)) | FIRMWARE_VERSION_TYPE_DEV,    // 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
    respondWithMavlinkMessage(msg);
}

818
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
819
{
820
    _missionItemHandler.setMissionItemFailureMode(failureMode);
821
}
822 823 824

void MockLink::_sendHomePosition(void)
{
825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842
    mavlink_message_t msg;

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

    mavlink_msg_home_position_pack(_vehicleSystemId,
                                   _vehicleComponentId,
                                   &msg,
                                   (int32_t)(_vehicleLatitude * 1E7),
                                   (int32_t)(_vehicleLongitude * 1E7),
                                   (int32_t)(_vehicleAltitude * 1000),
                                   0.0f, 0.0f, 0.0f,
                                   &bogus[0],
            0.0f, 0.0f, 0.0f);
    respondWithMavlinkMessage(msg);
843
}
Don Gagne's avatar
Don Gagne committed
844 845 846 847 848 849 850 851 852 853 854

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

    mavlink_msg_gps_raw_int_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &msg,
                                 timeTick++,                            // time since boot
                                 3,                                     // 3D fix
dogmaphobic's avatar
dogmaphobic committed
855
                                 (int32_t)(_vehicleLatitude  * 1E7),
Don Gagne's avatar
Don Gagne committed
856
                                 (int32_t)(_vehicleLongitude * 1E7),
dogmaphobic's avatar
dogmaphobic committed
857
                                 (int32_t)(_vehicleAltitude  * 1000),
Don Gagne's avatar
Don Gagne committed
858 859 860 861 862 863
                                 UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                 UINT16_MAX,                            // velocity not known
                                 UINT16_MAX,                            // course over ground not known
                                 8);                                    // satellite count
    respondWithMavlinkMessage(msg);
}
864

865 866 867 868 869 870 871 872
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
873 874 875 876 877 878 879 880 881 882
    { 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" },
};
883 884 885 886 887 888 889 890 891 892 893 894 895 896

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

        mavlink_msg_statustext_pack(_vehicleSystemId,
                                    _vehicleComponentId,
                                    &msg,
                                    status->severity,
                                    status->msg);
        respondWithMavlinkMessage(msg);
    }
}

897 898 899
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
900
    , _vehicleType(MAV_TYPE_QUADROTOR)
901
    , _sendStatusText(false)
902 903 904 905 906 907 908
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
909
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
910
    _vehicleType =      source->_vehicleType;
911
    _sendStatusText =   source->_sendStatusText;
912 913 914 915 916 917
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
918 919 920 921 922 923 924

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

    _firmwareType =     usource->_firmwareType;
925
    _vehicleType =      usource->_vehicleType;
926
    _sendStatusText =   usource->_sendStatusText;
927 928 929 930 931 932
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
933
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
934
    settings.setValue(_sendStatusTextKey, _sendStatusText);
935 936 937 938 939 940 941 942
    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();
943
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
944
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
945 946 947 948 949 950 951 952 953
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
954
            qWarning() << "updateSettings not supported";
955 956 957 958
            //ulink->_restartConnection();
        }
    }
}
959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013

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

    mockConfig->setDynamic(true);
    linkManager->linkConfigurations()->append(mockConfig);

    return qobject_cast<MockLink*>(linkManager->createConnectedLink(mockConfig));
}

MockLink*  MockLink::startPX4MockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startGenericMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &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

    respondWithMavlinkMessage(msg);

}
1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066

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;
    mavlink_msg_statustext_pack(_vehicleSystemId,
                                _vehicleComponentId,
                                &msg,
                                MAV_SEVERITY_INFO,
                                pCalMessage);
    respondWithMavlinkMessage(msg);
}