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

3
 QGroundControl Open Source Ground Control Station
4

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

7
 This file is part of the QGROUNDCONTROL project
8

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

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

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

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

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

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

#include <string.h>

33
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
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";
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
76

77 78 79 80 81 82 83 84 85 86
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)
Don Gagne's avatar
Don Gagne committed
87
    , _firmwareType(MAV_AUTOPILOT_PX4)
88
    , _fileServer(NULL)
89
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
90
    , _apmSendHomePositionOnEmptyList(false)
91
{
92
    _config = config;
93
    if (_config) {
Don Gagne's avatar
Don Gagne committed
94
        _firmwareType = config->firmwareType();
95
        _sendStatusText = config->sendStatusText();
96 97
    }

Don Gagne's avatar
Don Gagne committed
98 99 100 101 102 103
    union px4_custom_mode   px4_cm;

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

104 105 106
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
107
    moveToThread(this);
108
    
109 110 111 112 113 114
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
Daniel Agar's avatar
Daniel Agar committed
115
    qDebug() << "MockLink destructor";
116
    _disconnect();
117 118 119 120 121 122 123
}

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

124
bool MockLink::_connect(void)
125
{
126 127 128 129 130
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
131

132 133 134
    return true;
}

135
bool MockLink::_disconnect(void)
136
{
137 138
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
139 140
        quit();
        wait();
141 142
        emit disconnected();
    }
143

144 145 146 147 148 149 150 151
    return true;
}

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

153 154 155
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
156

157 158 159
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
160

161
    exec();
162

163 164 165
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
166 167
    
    _missionItemHandler.shutdown();
168 169 170 171
}

void MockLink::_run1HzTasks(void)
{
172
    if (_mavlinkStarted && _connected) {
173
        _sendHeartBeat();
174
        _sendHomePosition();
175 176 177 178
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
179 180 181 182 183
    }
}

void MockLink::_run10HzTasks(void)
{
184
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
185
        _sendGpsRawInt();
186 187 188 189 190
    }
}

void MockLink::_run50HzTasks(void)
{
191
    if (_mavlinkStarted && _connected) {
192 193 194 195 196
    }
}

void MockLink::_loadParams(void)
{
197
    QFile paramFile(":/unittest/MockLink.params");
198

199 200 201
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
202

203
    QTextStream paramStream(&paramFile);
204

205 206
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
207

208 209 210
        if (line.startsWith("#")) {
            continue;
        }
211

212 213
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
214

215
        int componentId = paramData.at(1).toInt();
216 217 218
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
219

220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237
        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;
        }
238

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

241
        _mapParamName2Value[componentId][paramName] = paramValue;
242
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
243 244 245 246 247 248 249 250 251 252 253
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
Don Gagne's avatar
Don Gagne committed
254
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
255 256
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
257
                               _mavState);          // MAV_STATE
258 259 260
    
    respondWithMavlinkMessage(msg);
}
261

262 263 264 265
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
266 267 268 269 270 271 272 273 274 275
    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);
276

277 278 279 280 281 282 283 284 285 286 287 288 289
    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);
        }
290

291 292 293 294 295 296 297 298
        _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);
299

300 301 302 303 304 305 306 307
    // 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;
308

309 310 311 312 313 314 315 316 317 318 319 320
        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;
321

322 323
    for (qint64 i=0; i<cBytes; i++)
    {
324
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
325 326
            continue;
        }
Don Gagne's avatar
Don Gagne committed
327
        
328
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
329 330
            continue;
        }
331

332 333 334 335
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
336

337 338 339
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
340

341 342 343
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
344

345 346 347
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
348

349 350 351
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
352 353 354 355
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
356 357 358 359
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
360

361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379
            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);
380

381
    Q_ASSERT(request.target_system == _vehicleSystemId);
382

383 384 385 386
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

387
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
388 389
{
    mavlink_param_union_t   valueUnion;
390

391 392
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
393
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
394

395
    valueUnion.param_float = paramFloat;
396

397
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
398

399
    QVariant paramVariant;
400

401 402 403 404
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
405

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

410 411 412
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
413

414 415 416
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
417

418 419
        default:
            qCritical() << "Invalid parameter type" << paramType;
420
    }
421

422
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
423
    _mapParamName2Value[componentId][paramName] = paramVariant;
424 425
}

426
/// Convert from a parameter variant to the float value from mavlink_param_union_t
427
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
428
{
429
    mavlink_param_union_t   valueUnion;
430

431 432
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
433
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
434

435
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
436
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
437

438 439
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
440
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
441 442 443 444
                valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
            } else {
                valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            }
445
            break;
446

447
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
448
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
449 450 451 452
                valueUnion.param_float = paramVar.toInt();
            } else {
                valueUnion.param_int32 = paramVar.toInt();
            }
453
            break;
454

455
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
456
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
457 458 459 460
                valueUnion.param_float = paramVar.toUInt();
            } else {
                valueUnion.param_uint32 = paramVar.toUInt();
            }
461
            break;
462

463
        case MAV_PARAM_TYPE_REAL32:
464
                valueUnion.param_float = paramVar.toFloat();
465
            break;
466

467 468 469
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
470

471
    return valueUnion.param_float;
472 473 474 475 476
}

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

478
    mavlink_msg_param_request_list_decode(&msg, &request);
479

480
    Q_ASSERT(request.target_system == _vehicleSystemId);
481
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
482 483 484
    
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
485 486

    foreach (int componentId, _mapParamName2Value.keys()) {
487
        uint16_t paramIndex = 0;
488 489 490 491 492 493 494 495 496 497 498 499 500 501
        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);

502
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
503 504 505 506 507 508 509 510 511

            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
512
            respondWithMavlinkMessage(responseMsg);
513 514 515 516 517 518 519 520 521 522 523 524 525 526
            
            // 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
527
                skipParam = false;
528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550
                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
551
                respondWithMavlinkMessage(responseMsg);
552
            }
553
        }
554 555 556 557 558 559 560
    }
}

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

562
    Q_ASSERT(request.target_system == _vehicleSystemId);
563
    int componentId = request.target_component;
Don Gagne's avatar
Don Gagne committed
564
    
565 566
    // 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
567
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
568
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
569

Don Gagne's avatar
Don Gagne committed
570 571
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
572 573
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
574
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
575

576
    // Save the new value
577
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
578

579 580 581
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
582 583 584 585 586 587 588
                                 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
589
    respondWithMavlinkMessage(responseMsg);
590 591 592 593
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
594
    mavlink_message_t   responseMsg;
595 596
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
597 598

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
599
    int componentId = request.target_component;
600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618

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

619
    Q_ASSERT(_mapParamName2Value.contains(componentId));
620

621 622
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
623

624
    Q_ASSERT(request.target_system == _vehicleSystemId);
625

626 627 628
    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);
629
    } else {
630
        // Request is by index
631

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

634
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
635 636
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
637
    }
638

639
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
640
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
641

642
    mavlink_msg_param_value_pack(_vehicleSystemId,
643 644 645 646 647 648 649
                                 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
650
    respondWithMavlinkMessage(responseMsg);
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 679 680 681 682 683 684 685 686
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
687 688 689 690 691 692 693
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
694
}
695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710

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

711 712 713 714
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
715 716 717

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

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);
}
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
void MockLink::_sendStatusTextMessages(void)
{
    struct StatusMessage {
        MAV_SEVERITY        severity;
        const char*         msg;
    };

    static const struct StatusMessage rgMessages[] = {
        { MAV_SEVERITY_INFO,        "#Testing audio output" },
        { MAV_SEVERITY_EMERGENCY,   "Status text emergency" },
        { MAV_SEVERITY_ALERT,       "Status text alert" },
        { MAV_SEVERITY_CRITICAL,    "Status text critical" },
        { MAV_SEVERITY_ERROR,       "Status text error" },
        { MAV_SEVERITY_WARNING,     "Status text warning" },
        { MAV_SEVERITY_NOTICE,      "Status text notice" },
        { MAV_SEVERITY_INFO,        "Status text info" },
        { MAV_SEVERITY_DEBUG,       "Status text debug" },
    };

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

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

790 791 792
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
793
    , _sendStatusText(false)
794 795 796 797 798 799 800
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
801 802
    _firmwareType =     source->_firmwareType;
    _sendStatusText =   source->_sendStatusText;
803 804 805 806 807 808
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
809 810 811 812 813 814 815 816

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

    _firmwareType =     usource->_firmwareType;
    _sendStatusText =   usource->_sendStatusText;
817 818 819 820 821 822
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
823
    settings.setValue(_sendStatusTextKey, _sendStatusText);
824 825 826 827 828 829 830 831
    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();
832
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
833 834 835 836 837 838 839 840 841
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
842
            qWarning() << "updateSettings not supported";
843 844 845 846
            //ulink->_restartConnection();
        }
    }
}