MockLink.cc 25.7 KB
Newer Older
1
/*=====================================================================
2

3
 QGroundControl Open Source Ground Control Station
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
6

7
 This file is part of the QGROUNDCONTROL project
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
21

22 23 24
 ======================================================================*/

#include "MockLink.h"
25
#include "QGCLoggingCategory.h"
26 27 28 29 30 31 32

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

#include <string.h>

33
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
34

35 36 37 38 39
/// @file
///     @brief Mock implementation of a Link.
///
///     @author Don Gagne <don@thegagnes.com>

Don Gagne's avatar
Don Gagne committed
40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68
enum PX4_CUSTOM_MAIN_MODE {
    PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
    PX4_CUSTOM_MAIN_MODE_ALTCTL,
    PX4_CUSTOM_MAIN_MODE_POSCTL,
    PX4_CUSTOM_MAIN_MODE_AUTO,
    PX4_CUSTOM_MAIN_MODE_ACRO,
    PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};

enum PX4_CUSTOM_SUB_MODE_AUTO {
    PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
    PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
    PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
    PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
    PX4_CUSTOM_SUB_MODE_AUTO_RTL,
    PX4_CUSTOM_SUB_MODE_AUTO_LAND,
    PX4_CUSTOM_SUB_MODE_AUTO_RTGS
};

union px4_custom_mode {
    struct {
        uint16_t reserved;
        uint8_t main_mode;
        uint8_t sub_mode;
    };
    uint32_t data;
    float data_float;
};

69
MockLink::MockLink(MockConfiguration* config) :
70 71 72 73 74 75
    _name("MockLink"),
    _connected(false),
    _vehicleSystemId(128),     // FIXME: Pull from eventual parameter manager
    _vehicleComponentId(200),  // FIXME: magic number?
    _inNSH(false),
    _mavlinkStarted(false),
Don Gagne's avatar
Don Gagne committed
76
    _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED),
77
    _mavState(MAV_STATE_STANDBY),
78 79
    _autopilotType(MAV_AUTOPILOT_PX4),
    _fileServer(NULL)
80
{
81
    _config = config;
Don Gagne's avatar
Don Gagne committed
82 83 84 85 86 87
    union px4_custom_mode   px4_cm;

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

88 89 90
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
91 92
    _missionItemHandler = new MockLinkMissionItemHandler(_vehicleSystemId, this);
    Q_CHECK_PTR(_missionItemHandler);
93

94 95 96 97 98 99 100
    moveToThread(this);
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
101
    _disconnect();
102 103 104 105 106 107 108
}

void MockLink::readBytes(void)
{
    // FIXME: This is a bad virtual from LinkInterface?
}

109
bool MockLink::_connect(void)
110
{
111 112 113 114 115
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
116

117 118 119
    return true;
}

120
bool MockLink::_disconnect(void)
121
{
122 123
    if (_connected) {
        _connected = false;
124
        exit();
125 126
        emit disconnected();
    }
127

128 129 130 131 132 133 134 135
    return true;
}

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

137 138 139
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
140

141 142 143
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
144

145
    exec();
146

147 148 149
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
150 151 152 153
}

void MockLink::_run1HzTasks(void)
{
154
    if (_mavlinkStarted && _connected) {
155 156 157 158 159 160
        _sendHeartBeat();
    }
}

void MockLink::_run10HzTasks(void)
{
161
    if (_mavlinkStarted && _connected) {
162 163 164 165 166
    }
}

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

void MockLink::_loadParams(void)
{
173
    QFile paramFile(":/unittest/MockLink.params");
174

175 176 177
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
178

179
    QTextStream paramStream(&paramFile);
180

181 182
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
183

184 185 186
        if (line.startsWith("#")) {
            continue;
        }
187

188 189
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
190

191
        int componentId = paramData.at(1).toInt();
192 193 194
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
195

196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213
        QVariant paramValue;
        switch (paramType) {
            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_INT8:
                paramValue = QVariant((unsigned char)valStr.toUInt());
                break;
            default:
                Q_ASSERT(false);
                break;
        }
214

Don Gagne's avatar
Don Gagne committed
215
        qCDebug(MockLinkLog) << "Loading param" << paramName << paramValue;
216

217
        _mapParamName2Value[componentId][paramName] = paramValue;
218
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
219 220 221 222 223 224 225 226 227 228 229
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
230
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
231 232
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
233
                               _mavState);          // MAV_STATE
234 235 236
    
    respondWithMavlinkMessage(msg);
}
237

238 239 240 241
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
242 243 244 245 246 247 248 249 250 251
    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
void MockLink::writeBytes(const char* bytes, qint64 cBytes)
{
    // Package up the data so we can signal it over to the right thread
    QByteArray byteArray(bytes, cBytes);
252

253 254 255 256 257 258 259 260 261 262 263 264 265
    emit _incomingBytes(byteArray);
}

/// @brief Handles bytes from QGC on the thread
void MockLink::_handleIncomingBytes(const QByteArray bytes)
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
266

267 268 269 270 271 272 273 274
        _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);
275

276 277 278 279 280 281 282 283
    // 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;
284

285 286 287 288 289 290 291 292 293 294 295 296
        if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
            // This is the mavlink start command
            _mavlinkStarted = true;
        }
    }
}

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

298 299
    for (qint64 i=0; i<cBytes; i++)
    {
300
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
301 302
            continue;
        }
303

304 305
        Q_ASSERT(_missionItemHandler);
        _missionItemHandler->handleMessage(msg);
306

307 308 309 310
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
311

312 313 314
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
315

316 317 318
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
319

320 321 322
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
323

324 325 326
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
327

328 329 330
            case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
                _handleMissionRequestList(msg);
                break;
331

332 333 334
            case MAVLINK_MSG_ID_MISSION_REQUEST:
                _handleMissionRequest(msg);
                break;
335

336 337 338
            case MAVLINK_MSG_ID_MISSION_ITEM:
                _handleMissionItem(msg);
                break;
339

340 341 342 343 344
#if 0
            case MAVLINK_MSG_ID_MISSION_COUNT:
                _handleMissionCount(msg);
                break;
#endif
345 346 347 348
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
349

350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369
            default:
                qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid;
                break;
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
#if 0
    mavlink_heartbeat_t heartbeat;
    mavlink_msg_heartbeat_decode(&msg, &heartbeat);
#endif
}

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

371
    Q_ASSERT(request.target_system == _vehicleSystemId);
372

373 374 375 376
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

377
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
378 379
{
    mavlink_param_union_t   valueUnion;
380

381 382
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
383
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
384

385
    valueUnion.param_float = paramFloat;
386

387
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
388

389
    QVariant paramVariant;
390

391 392 393 394
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
395

396 397 398
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
399

400 401 402
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
403

404 405 406
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
407

408 409
        default:
            qCritical() << "Invalid parameter type" << paramType;
410
    }
411

412
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
413
    _mapParamName2Value[componentId][paramName] = paramVariant;
414 415
}

416
/// Convert from a parameter variant to the float value from mavlink_param_union_t
417
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
418
{
419
    mavlink_param_union_t   valueUnion;
420

421 422
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
423
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
424

425
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
426
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
427

428 429
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
430 431 432 433 434
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
            } else {
                valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            }
435
            break;
436

437
        case MAV_PARAM_TYPE_INT32:
438 439 440 441 442
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toInt();
            } else {
                valueUnion.param_int32 = paramVar.toInt();
            }
443
            break;
444

445
        case MAV_PARAM_TYPE_UINT32:
446 447 448 449 450
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toUInt();
            } else {
                valueUnion.param_uint32 = paramVar.toUInt();
            }
451
            break;
452

453
        case MAV_PARAM_TYPE_REAL32:
454
                valueUnion.param_float = paramVar.toFloat();
455
            break;
456

457 458 459
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
460

461
    return valueUnion.param_float;
462 463 464 465 466
}

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

468
    mavlink_msg_param_request_list_decode(&msg, &request);
469

470
    Q_ASSERT(request.target_system == _vehicleSystemId);
471
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
472 473 474
    
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
475 476

    foreach (int componentId, _mapParamName2Value.keys()) {
477
        uint16_t paramIndex = 0;
478 479 480 481 482 483 484 485 486 487 488 489 490 491
        int cParameters = _mapParamName2Value[componentId].count();
        
        foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
            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);

492
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
493 494 495 496 497 498 499 500 501

            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
502
            respondWithMavlinkMessage(responseMsg);
503 504 505 506 507 508 509 510 511 512 513 514 515 516
            
            // Only first parameter the first time through
            break;
        }
    }
    
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
        
        foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
517
                skipParam = false;
518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540
                paramIndex++;
            } else {
                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);
                
                qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
                
                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
541
                respondWithMavlinkMessage(responseMsg);
542
            }
543
        }
544 545 546 547 548 549 550
    }
}

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

552
    Q_ASSERT(request.target_system == _vehicleSystemId);
553
    int componentId = request.target_component;
Don Gagne's avatar
Don Gagne committed
554
    
555 556
    // 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
557
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
558
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
559

Don Gagne's avatar
Don Gagne committed
560 561
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
562 563
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
564
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
565

566
    // Save the new value
567
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
568

569 570 571
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
572 573 574 575 576 577 578
                                 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
579
    respondWithMavlinkMessage(responseMsg);
580 581 582 583 584 585
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
586 587 588
    
    int componentId = request.target_component;
    Q_ASSERT(_mapParamName2Value.contains(componentId));
589

590 591
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
592

593
    Q_ASSERT(request.target_system == _vehicleSystemId);
594

595 596 597
    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);
598
    } else {
599
        // Request is by index
600

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

603
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
604 605
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
606
    }
607

608
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
609
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
610

611
    mavlink_message_t   responseMsg;
612

613
    mavlink_msg_param_value_pack(_vehicleSystemId,
614 615 616 617 618 619 620
                                 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
621
    respondWithMavlinkMessage(responseMsg);
622 623 624 625 626
}

void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
{
    mavlink_mission_request_list_t request;
627

628
    mavlink_msg_mission_request_list_decode(&msg, &request);
629

630
    Q_ASSERT(request.target_system == _vehicleSystemId);
631

632 633 634 635 636 637 638 639
    mavlink_message_t   responseMsg;

    mavlink_msg_mission_count_pack(_vehicleSystemId,
                                   _vehicleComponentId,
                                   &responseMsg,            // Outgoing message
                                   msg.sysid,               // Target is original sender
                                   msg.compid,              // Target is original sender
                                   _missionItems.count());  // Number of mission items
640
    respondWithMavlinkMessage(responseMsg);
641 642 643 644 645
}

void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
{
    mavlink_mission_request_t request;
646

647
    mavlink_msg_mission_request_decode(&msg, &request);
648

649 650
    Q_ASSERT(request.target_system == _vehicleSystemId);
    Q_ASSERT(request.seq < _missionItems.count());
651

652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667
    mavlink_message_t   responseMsg;

    mavlink_mission_item_t item = _missionItems[request.seq];

    mavlink_msg_mission_item_pack(_vehicleSystemId,
                                  _vehicleComponentId,
                                  &responseMsg,            // Outgoing message
                                  msg.sysid,               // Target is original sender
                                  msg.compid,              // Target is original sender
                                  request.seq,             // Index of mission item being sent
                                  item.frame,
                                  item.command,
                                  item.current,
                                  item.autocontinue,
                                  item.param1, item.param2, item.param3, item.param4,
                                  item.x, item.y, item.z);
668
    respondWithMavlinkMessage(responseMsg);
669 670 671 672 673
}

void MockLink::_handleMissionItem(const mavlink_message_t& msg)
{
    mavlink_mission_item_t request;
674

675
    mavlink_msg_mission_item_decode(&msg, &request);
676

677
    Q_ASSERT(request.target_system == _vehicleSystemId);
678

679 680
    // FIXME: What do you do with duplication sequence numbers?
    Q_ASSERT(!_missionItems.contains(request.seq));
681

682
    _missionItems[request.seq] = request;
683
}
684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718

void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
    
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
    
    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
                                 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
719 720 721 722 723 724 725
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
726
}