MockLink.cc 26.5 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;
};

Don Gagne's avatar
Don Gagne committed
70 71 72 73
float MockLink::_vehicleLatitude =  47.633033f;
float MockLink::_vehicleLongitude = -122.08794f;
float MockLink::_vehicleAltitude =  2.5f;

74 75 76 77 78 79 80 81 82 83 84 85
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)
86
{
87
    _config = config;
Don Gagne's avatar
Don Gagne committed
88 89 90 91 92 93
    union px4_custom_mode   px4_cm;

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

94 95 96
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
97
    moveToThread(this);
98
    
99 100 101 102 103 104
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
Daniel Agar's avatar
Daniel Agar committed
105
    qDebug() << "MockLink destructor";
106
    _disconnect();
107 108 109 110 111 112 113
}

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

114
bool MockLink::_connect(void)
115
{
116 117 118 119 120
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
121

122 123 124
    return true;
}

125
bool MockLink::_disconnect(void)
126
{
127 128
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
129 130
        quit();
        wait();
131 132
        emit disconnected();
    }
133

134 135 136 137 138 139 140 141
    return true;
}

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

143 144 145
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
146

147 148 149
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
150

151
    exec();
152

153 154 155
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
156 157
    
    _missionItemHandler.shutdown();
158 159 160 161
}

void MockLink::_run1HzTasks(void)
{
162
    if (_mavlinkStarted && _connected) {
163
        _sendHeartBeat();
164
        _sendHomePosition();
165 166 167 168 169
    }
}

void MockLink::_run10HzTasks(void)
{
170
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
171
        _sendGpsRawInt();
172 173 174 175 176
    }
}

void MockLink::_run50HzTasks(void)
{
177
    if (_mavlinkStarted && _connected) {
178 179 180 181 182
    }
}

void MockLink::_loadParams(void)
{
183
    QFile paramFile(":/unittest/MockLink.params");
184

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

189
    QTextStream paramStream(&paramFile);
190

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

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

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

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

206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223
        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;
        }
224

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

227
        _mapParamName2Value[componentId][paramName] = paramValue;
228
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
229 230 231 232 233 234 235 236 237 238 239
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
240
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
241 242
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
243
                               _mavState);          // MAV_STATE
244 245 246
    
    respondWithMavlinkMessage(msg);
}
247

248 249 250 251
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
252 253 254 255 256 257 258 259 260 261
    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);
262

263 264 265 266 267 268 269 270 271 272 273 274 275
    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);
        }
276

277 278 279 280 281 282 283 284
        _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);
285

286 287 288 289 290 291 292 293
    // 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;
294

295 296 297 298 299 300 301 302 303 304 305 306
        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;
307

308 309
    for (qint64 i=0; i<cBytes; i++)
    {
310
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
311 312
            continue;
        }
Don Gagne's avatar
Don Gagne committed
313
        
314
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
315 316
            continue;
        }
317

318 319 320 321
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
322

323 324 325
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
326

327 328 329
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
330

331 332 333
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
334

335 336 337
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
338 339 340 341
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
342 343 344 345
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
346

347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365
            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);
366

367
    Q_ASSERT(request.target_system == _vehicleSystemId);
368

369 370 371 372
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

373
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
374 375
{
    mavlink_param_union_t   valueUnion;
376

377 378
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
379
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
380

381
    valueUnion.param_float = paramFloat;
382

383
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
384

385
    QVariant paramVariant;
386

387 388 389 390
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
391

392 393 394
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
395

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

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

404 405
        default:
            qCritical() << "Invalid parameter type" << paramType;
406
    }
407

408
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
409
    _mapParamName2Value[componentId][paramName] = paramVariant;
410 411
}

412
/// Convert from a parameter variant to the float value from mavlink_param_union_t
413
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
414
{
415
    mavlink_param_union_t   valueUnion;
416

417 418
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
419
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
420

421
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
422
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
423

424 425
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
426 427 428 429 430
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
            } else {
                valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            }
431
            break;
432

433
        case MAV_PARAM_TYPE_INT32:
434 435 436 437 438
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toInt();
            } else {
                valueUnion.param_int32 = paramVar.toInt();
            }
439
            break;
440

441
        case MAV_PARAM_TYPE_UINT32:
442 443 444 445 446
            if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
                valueUnion.param_float = paramVar.toUInt();
            } else {
                valueUnion.param_uint32 = paramVar.toUInt();
            }
447
            break;
448

449
        case MAV_PARAM_TYPE_REAL32:
450
                valueUnion.param_float = paramVar.toFloat();
451
            break;
452

453 454 455
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
456

457
    return valueUnion.param_float;
458 459 460 461 462
}

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

464
    mavlink_msg_param_request_list_decode(&msg, &request);
465

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

    foreach (int componentId, _mapParamName2Value.keys()) {
473
        uint16_t paramIndex = 0;
474 475 476 477 478 479 480 481 482 483 484 485 486 487
        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);

488
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
489 490 491 492 493 494 495 496 497

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

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

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

Don Gagne's avatar
Don Gagne committed
556 557
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
558 559
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
560
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
561

562
    // Save the new value
563
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
564

565 566 567
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
568 569 570 571 572 573 574
                                 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
575
    respondWithMavlinkMessage(responseMsg);
576 577 578 579
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
580
    mavlink_message_t   responseMsg;
581 582
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
583 584

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
585
    int componentId = request.target_component;
586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604

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

605
    Q_ASSERT(_mapParamName2Value.contains(componentId));
606

607 608
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
609

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

612 613 614
    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);
615
    } else {
616
        // Request is by index
617

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

620
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
621 622
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
623
    }
624

625
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
626
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
627

628
    mavlink_msg_param_value_pack(_vehicleSystemId,
629 630 631 632 633 634 635
                                 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
636
    respondWithMavlinkMessage(responseMsg);
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 668 669 670 671 672
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
673 674 675 676 677 678 679
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
680
}
681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696

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

697 698 699 700
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
701 702 703

void MockLink::_sendHomePosition(void)
{
Don Gagne's avatar
Don Gagne committed
704
    mavlink_message_t msg;
705 706 707 708 709 710 711 712 713 714
    
    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,
Don Gagne's avatar
Don Gagne committed
715 716 717
                                   (int32_t)(_vehicleLatitude * 1E7),
                                   (int32_t)(_vehicleLongitude * 1E7),
                                   (int32_t)(_vehicleAltitude * 1000),
718 719 720 721 722
                                   0.0f, 0.0f, 0.0f,
                                   &bogus[0],
                                   0.0f, 0.0f, 0.0f);
    respondWithMavlinkMessage(msg);
}
Don Gagne's avatar
Don Gagne committed
723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742

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
                                 (int32_t)(_vehicleLatitude * 1E7),
                                 (int32_t)(_vehicleLongitude * 1E7),
                                 (int32_t)(_vehicleAltitude * 1000),
                                 UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                 UINT16_MAX,                            // velocity not known
                                 UINT16_MAX,                            // course over ground not known
                                 8);                                    // satellite count
    respondWithMavlinkMessage(msg);
}