MockLink.cc 30.1 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
    , _sendHomePositionDelayCount(2)
92
{
93
    _config = config;
94
    if (_config) {
Don Gagne's avatar
Don Gagne committed
95
        _firmwareType = config->firmwareType();
96
        _sendStatusText = config->sendStatusText();
97 98
    }

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

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

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

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

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

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

133 134 135
    return true;
}

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

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

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

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

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

162
    exec();
163

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

void MockLink::_run1HzTasks(void)
{
173
    if (_mavlinkStarted && _connected) {
174
        _sendHeartBeat();
175 176 177 178 179 180
        if (_sendHomePositionDelayCount > 0) {
            // We delay home position a bit to be more realistic
            _sendHomePositionDelayCount--;
        } else {
            _sendHomePosition();
        }
181 182 183 184
        if (_sendStatusText) {
            _sendStatusText = false;
            _sendStatusTextMessages();
        }
185 186 187 188 189
    }
}

void MockLink::_run10HzTasks(void)
{
190
    if (_mavlinkStarted && _connected) {
Don Gagne's avatar
Don Gagne committed
191
        _sendGpsRawInt();
192 193 194 195 196
    }
}

void MockLink::_run50HzTasks(void)
{
197
    if (_mavlinkStarted && _connected) {
198 199 200 201 202
    }
}

void MockLink::_loadParams(void)
{
203
    QFile paramFile(":/unittest/MockLink.params");
204

205 206 207
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
208

209
    QTextStream paramStream(&paramFile);
210

211 212
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
213

214 215 216
        if (line.startsWith("#")) {
            continue;
        }
217

218 219
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
220

221
        int componentId = paramData.at(1).toInt();
222 223 224
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
225

226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243
        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;
        }
244

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

247
        _mapParamName2Value[componentId][paramName] = paramValue;
248
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
249 250 251 252 253 254 255 256 257 258 259
    }
}

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
260
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
261 262
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
263
                               _mavState);          // MAV_STATE
264 265 266
    
    respondWithMavlinkMessage(msg);
}
267

268 269 270 271
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
272 273 274 275 276 277 278 279 280 281
    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);
282

283 284 285 286 287 288 289 290 291 292 293 294 295
    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);
        }
296

297 298 299 300 301 302 303 304
        _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);
305

306 307 308 309 310 311 312 313
    // 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;
314

315 316 317 318 319 320 321 322 323 324 325 326
        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;
327

328 329
    for (qint64 i=0; i<cBytes; i++)
    {
330
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
331 332
            continue;
        }
Don Gagne's avatar
Don Gagne committed
333
        
334
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
335 336
            continue;
        }
337

338 339 340 341
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
342

343 344 345
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
346

347 348 349
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
350

351 352 353
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
354

355 356 357
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
358 359 360 361
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
362 363 364 365
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
366

367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385
            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);
386

387
    Q_ASSERT(request.target_system == _vehicleSystemId);
388

389 390 391 392
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

393
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
394 395
{
    mavlink_param_union_t   valueUnion;
396

397 398
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
399
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
400

401
    valueUnion.param_float = paramFloat;
402

403
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
404

405
    QVariant paramVariant;
406

407 408 409 410
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
411

412 413 414
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
415

416 417 418
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
419

420 421 422
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
423

424 425
        default:
            qCritical() << "Invalid parameter type" << paramType;
426
    }
427

428
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
429
    _mapParamName2Value[componentId][paramName] = paramVariant;
430 431
}

432
/// Convert from a parameter variant to the float value from mavlink_param_union_t
433
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
434
{
435
    mavlink_param_union_t   valueUnion;
436

437 438
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
439
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
440

441
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
442
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
443

444 445
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
Don Gagne's avatar
Don Gagne committed
446
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
447 448 449 450
                valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
            } else {
                valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            }
451
            break;
452

453
        case MAV_PARAM_TYPE_INT32:
Don Gagne's avatar
Don Gagne committed
454
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
455 456 457 458
                valueUnion.param_float = paramVar.toInt();
            } else {
                valueUnion.param_int32 = paramVar.toInt();
            }
459
            break;
460

461
        case MAV_PARAM_TYPE_UINT32:
Don Gagne's avatar
Don Gagne committed
462
            if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
463 464 465 466
                valueUnion.param_float = paramVar.toUInt();
            } else {
                valueUnion.param_uint32 = paramVar.toUInt();
            }
467
            break;
468

469
        case MAV_PARAM_TYPE_REAL32:
470
                valueUnion.param_float = paramVar.toFloat();
471
            break;
472

473 474 475
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
476

477
    return valueUnion.param_float;
478 479 480 481 482
}

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

484
    mavlink_msg_param_request_list_decode(&msg, &request);
485

486
    Q_ASSERT(request.target_system == _vehicleSystemId);
487
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
488 489 490
    
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
491 492

    foreach (int componentId, _mapParamName2Value.keys()) {
493
        uint16_t paramIndex = 0;
494 495 496 497 498 499 500 501 502 503 504 505 506 507
        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);

508
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
509 510 511 512 513 514 515 516 517

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

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

568
    Q_ASSERT(request.target_system == _vehicleSystemId);
569
    int componentId = request.target_component;
Don Gagne's avatar
Don Gagne committed
570
    
571 572
    // 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
573
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
574
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
575

Don Gagne's avatar
Don Gagne committed
576 577
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
578 579
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
580
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
581

582
    // Save the new value
583
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
584

585 586 587
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
588 589 590 591 592 593 594
                                 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
595
    respondWithMavlinkMessage(responseMsg);
596 597 598 599
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
600
    mavlink_message_t   responseMsg;
601 602
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
603 604

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
605
    int componentId = request.target_component;
606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624

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

625
    Q_ASSERT(_mapParamName2Value.contains(componentId));
626

627 628
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
629

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

632 633 634
    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);
635
    } else {
636
        // Request is by index
637

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

640
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
641 642
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
643
    }
644

645
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
646
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
647

648
    mavlink_msg_param_value_pack(_vehicleSystemId,
649 650 651 652 653 654 655
                                 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
656
    respondWithMavlinkMessage(responseMsg);
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 687 688 689 690 691 692
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
693 694 695 696 697 698 699
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
700
}
701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716

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

717 718 719 720
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
721 722 723

void MockLink::_sendHomePosition(void)
{
724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746
    // APM stack does not yet support HOME_POSITION

    if (_firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {

        mavlink_message_t msg;

        float bogus[4];
        bogus[0] = 0.0f;
        bogus[1] = 0.0f;
        bogus[2] = 0.0f;
        bogus[3] = 0.0f;

        mavlink_msg_home_position_pack(_vehicleSystemId,
                                       _vehicleComponentId,
                                       &msg,
                                       (int32_t)(_vehicleLatitude * 1E7),
                                       (int32_t)(_vehicleLongitude * 1E7),
                                       (int32_t)(_vehicleAltitude * 1000),
                                       0.0f, 0.0f, 0.0f,
                                       &bogus[0],
                0.0f, 0.0f, 0.0f);
        respondWithMavlinkMessage(msg);
    }
747
}
Don Gagne's avatar
Don Gagne committed
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767

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);
}
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 797 798 799 800
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);
    }
}

801 802 803
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
804
    , _sendStatusText(false)
805 806 807 808 809 810 811
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
812 813
    _firmwareType =     source->_firmwareType;
    _sendStatusText =   source->_sendStatusText;
814 815 816 817 818 819
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
820 821 822 823 824 825 826 827

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

    _firmwareType =     usource->_firmwareType;
    _sendStatusText =   usource->_sendStatusText;
828 829 830 831 832 833
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
834
    settings.setValue(_sendStatusTextKey, _sendStatusText);
835 836 837 838 839 840 841 842
    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();
843
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
844 845 846 847 848 849 850 851 852
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
853
            qWarning() << "updateSettings not supported";
854 855 856 857
            //ulink->_restartConnection();
        }
    }
}