MockLink.cc 25.3 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")
Don Gagne's avatar
Don Gagne committed
34
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
35

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

Don Gagne's avatar
Don Gagne committed
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 69
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;
};

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

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

90 91 92
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
93
    moveToThread(this);
94
    
95 96 97 98 99 100
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
Daniel Agar's avatar
Daniel Agar committed
101
    qDebug() << "MockLink destructor";
102
    _disconnect();
103 104 105 106 107 108 109
}

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

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

118 119 120
    return true;
}

121
bool MockLink::_disconnect(void)
122
{
123 124
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
125 126
        quit();
        wait();
127 128
        emit disconnected();
    }
129

130 131 132 133 134 135 136 137
    return true;
}

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

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

143 144 145
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
146

147
    exec();
148

149 150 151
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
152 153
    
    _missionItemHandler.shutdown();
154 155 156 157
}

void MockLink::_run1HzTasks(void)
{
158
    if (_mavlinkStarted && _connected) {
159
        _sendHeartBeat();
160
        _sendHomePosition();
161 162 163 164 165
    }
}

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

void MockLink::_run50HzTasks(void)
{
172
    if (_mavlinkStarted && _connected) {
173 174 175 176 177
    }
}

void MockLink::_loadParams(void)
{
178
    QFile paramFile(":/unittest/MockLink.params");
179

180 181 182
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
183

184
    QTextStream paramStream(&paramFile);
185

186 187
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
188

189 190 191
        if (line.startsWith("#")) {
            continue;
        }
192

193 194
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
195

196
        int componentId = paramData.at(1).toInt();
197 198 199
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
200

201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
        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;
        }
219

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

222
        _mapParamName2Value[componentId][paramName] = paramValue;
223
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
224 225 226 227 228 229 230 231 232 233 234
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
235
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
236 237
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
238
                               _mavState);          // MAV_STATE
239 240 241
    
    respondWithMavlinkMessage(msg);
}
242

243 244 245 246
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
247 248 249 250 251 252 253 254 255 256
    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);
257

258 259 260 261 262 263 264 265 266 267 268 269 270
    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);
        }
271

272 273 274 275 276 277 278 279
        _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);
280

281 282 283 284 285 286 287 288
    // 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;
289

290 291 292 293 294 295 296 297 298 299 300 301
        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;
302

303 304
    for (qint64 i=0; i<cBytes; i++)
    {
305
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
306 307
            continue;
        }
Don Gagne's avatar
Don Gagne committed
308
        
309
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
310 311
            continue;
        }
312

313 314 315 316
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
317

318 319 320
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
321

322 323 324
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
325

326 327 328
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
329

330 331 332
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
333 334 335 336
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
337 338 339 340
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
341

342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360
            default:
                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);
361

362
    Q_ASSERT(request.target_system == _vehicleSystemId);
363

364 365 366 367
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

368
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
369 370
{
    mavlink_param_union_t   valueUnion;
371

372 373
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
374
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
375

376
    valueUnion.param_float = paramFloat;
377

378
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
379

380
    QVariant paramVariant;
381

382 383 384 385
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
386

387 388 389
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
390

391 392 393
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
394

395 396 397
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
398

399 400
        default:
            qCritical() << "Invalid parameter type" << paramType;
401
    }
402

403
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
404
    _mapParamName2Value[componentId][paramName] = paramVariant;
405 406
}

407
/// Convert from a parameter variant to the float value from mavlink_param_union_t
408
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
409
{
410
    mavlink_param_union_t   valueUnion;
411

412 413
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
414
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
415

416
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
417
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
418

419 420
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
421 422 423 424 425
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
            } else {
                valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            }
426
            break;
427

428
        case MAV_PARAM_TYPE_INT32:
429 430 431 432 433
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toInt();
            } else {
                valueUnion.param_int32 = paramVar.toInt();
            }
434
            break;
435

436
        case MAV_PARAM_TYPE_UINT32:
437 438 439 440 441
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toUInt();
            } else {
                valueUnion.param_uint32 = paramVar.toUInt();
            }
442
            break;
443

444
        case MAV_PARAM_TYPE_REAL32:
445
                valueUnion.param_float = paramVar.toFloat();
446
            break;
447

448 449 450
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
451

452
    return valueUnion.param_float;
453 454 455 456 457
}

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

459
    mavlink_msg_param_request_list_decode(&msg, &request);
460

461
    Q_ASSERT(request.target_system == _vehicleSystemId);
462
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
463 464 465
    
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
466 467

    foreach (int componentId, _mapParamName2Value.keys()) {
468
        uint16_t paramIndex = 0;
469 470 471 472 473 474 475 476 477 478 479 480 481 482
        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);

483
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
484 485 486 487 488 489 490 491 492

            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
493
            respondWithMavlinkMessage(responseMsg);
494 495 496 497 498 499 500 501 502 503 504 505 506 507
            
            // 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
508
                skipParam = false;
509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531
                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
532
                respondWithMavlinkMessage(responseMsg);
533
            }
534
        }
535 536 537 538 539 540 541
    }
}

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

543
    Q_ASSERT(request.target_system == _vehicleSystemId);
544
    int componentId = request.target_component;
Don Gagne's avatar
Don Gagne committed
545
    
546 547
    // 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
548
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
549
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
550

Don Gagne's avatar
Don Gagne committed
551 552
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
553 554
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
555
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
556

557
    // Save the new value
558
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
559

560 561 562
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
563 564 565 566 567 568 569
                                 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
570
    respondWithMavlinkMessage(responseMsg);
571 572 573 574
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
575
    mavlink_message_t   responseMsg;
576 577
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
578 579

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
580
    int componentId = request.target_component;
581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599

    // 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;
    }

600
    Q_ASSERT(_mapParamName2Value.contains(componentId));
601

602 603
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
604

605
    Q_ASSERT(request.target_system == _vehicleSystemId);
606

607 608 609
    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);
610
    } else {
611
        // Request is by index
612

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

615
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
616 617
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
618
    }
619

620
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
621
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
622

623
    mavlink_msg_param_value_pack(_vehicleSystemId,
624 625 626 627 628 629 630
                                 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
631
    respondWithMavlinkMessage(responseMsg);
632 633
}

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

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
675
}
676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
    mavlink_command_long_t request;
    
    mavlink_msg_command_long_decode(&msg, &request);

    if (request.command == MAV_CMD_COMPONENT_ARM_DISARM) {
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
    }
}

692 693 694 695
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717

void MockLink::_sendHomePosition(void)
{
    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)(47.633033f * 1E7),
                                   (int32_t)(-122.08794f * 1E7),
                                   (int32_t)(2.0f * 1000),
                                   0.0f, 0.0f, 0.0f,
                                   &bogus[0],
                                   0.0f, 0.0f, 0.0f);
    respondWithMavlinkMessage(msg);
}