MockLink.cc 27.9 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
const char* MockConfiguration::_firmwareTypeKey = "FirmwareType";

76 77 78 79 80 81 82 83 84 85 86 87
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)
88
{
89
    _config = config;
90 91 92 93
    if (_config) {
        _autopilotType = config->firmwareType();
    }

Don Gagne's avatar
Don Gagne committed
94 95 96 97 98 99
    union px4_custom_mode   px4_cm;

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

100 101 102
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
103
    moveToThread(this);
104
    
105 106 107 108 109 110
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
Daniel Agar's avatar
Daniel Agar committed
111
    qDebug() << "MockLink destructor";
112
    _disconnect();
113 114 115 116 117 118 119
}

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

120
bool MockLink::_connect(void)
121
{
122 123 124 125 126
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
127

128 129 130
    return true;
}

131
bool MockLink::_disconnect(void)
132
{
133 134
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
135 136
        quit();
        wait();
137 138
        emit disconnected();
    }
139

140 141 142 143 144 145 146 147
    return true;
}

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

149 150 151
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
152

153 154 155
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
156

157
    exec();
158

159 160 161
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
162 163
    
    _missionItemHandler.shutdown();
164 165 166 167
}

void MockLink::_run1HzTasks(void)
{
168
    if (_mavlinkStarted && _connected) {
169
        _sendHeartBeat();
170
        _sendHomePosition();
171 172 173 174 175
    }
}

void MockLink::_run10HzTasks(void)
{
176
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
177
        _sendGpsRawInt();
178 179 180 181 182
    }
}

void MockLink::_run50HzTasks(void)
{
183
    if (_mavlinkStarted && _connected) {
184 185 186 187 188
    }
}

void MockLink::_loadParams(void)
{
189
    QFile paramFile(":/unittest/MockLink.params");
190

191 192 193
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
194

195
    QTextStream paramStream(&paramFile);
196

197 198
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
199

200 201 202
        if (line.startsWith("#")) {
            continue;
        }
203

204 205
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
206

207
        int componentId = paramData.at(1).toInt();
208 209 210
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
211

212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229
        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;
        }
230

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

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

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
246
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
247 248
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
249
                               _mavState);          // MAV_STATE
250 251 252
    
    respondWithMavlinkMessage(msg);
}
253

254 255 256 257
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
258 259 260 261 262 263 264 265 266 267
    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);
268

269 270 271 272 273 274 275 276 277 278 279 280 281
    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);
        }
282

283 284 285 286 287 288 289 290
        _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);
291

292 293 294 295 296 297 298 299
    // 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;
300

301 302 303 304 305 306 307 308 309 310 311 312
        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;
313

314 315
    for (qint64 i=0; i<cBytes; i++)
    {
316
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
317 318
            continue;
        }
Don Gagne's avatar
Don Gagne committed
319
        
320
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
321 322
            continue;
        }
323

324 325 326 327
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
328

329 330 331
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
332

333 334 335
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
336

337 338 339
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
340

341 342 343
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
344 345 346 347
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
348 349 350 351
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
352

353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371
            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);
372

373
    Q_ASSERT(request.target_system == _vehicleSystemId);
374

375 376 377 378
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

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

383 384
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
385
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
386

387
    valueUnion.param_float = paramFloat;
388

389
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
390

391
    QVariant paramVariant;
392

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

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

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

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

410 411
        default:
            qCritical() << "Invalid parameter type" << paramType;
412
    }
413

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

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

423 424
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
425
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
426

427
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
428
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
429

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

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

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

455
        case MAV_PARAM_TYPE_REAL32:
456
                valueUnion.param_float = paramVar.toFloat();
457
            break;
458

459 460 461
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
462

463
    return valueUnion.param_float;
464 465 466 467 468
}

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

470
    mavlink_msg_param_request_list_decode(&msg, &request);
471

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

    foreach (int componentId, _mapParamName2Value.keys()) {
479
        uint16_t paramIndex = 0;
480 481 482 483 484 485 486 487 488 489 490 491 492 493
        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);

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

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

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

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

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

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

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

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
586
    mavlink_message_t   responseMsg;
587 588
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
589 590

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
591
    int componentId = request.target_component;
592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610

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

611
    Q_ASSERT(_mapParamName2Value.contains(componentId));
612

613 614
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
615

616
    Q_ASSERT(request.target_system == _vehicleSystemId);
617

618 619 620
    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);
621
    } else {
622
        // Request is by index
623

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

626
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
627 628
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
629
    }
630

631
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
632
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
633

634
    mavlink_msg_param_value_pack(_vehicleSystemId,
635 636 637 638 639 640 641
                                 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
642
    respondWithMavlinkMessage(responseMsg);
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 673 674 675 676 677 678
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
679 680 681 682 683 684 685
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
686
}
687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702

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

703 704 705 706
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
707 708 709

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

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);
}
749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796

MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
    _firmwareType = source->_firmwareType;
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
    Q_ASSERT(usource != NULL);
    _firmwareType = usource->_firmwareType;
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
    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();
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
            Q_ASSERT(false);
            //ulink->_restartConnection();
        }
    }
}