MockLink.cc 34.4 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
#include "QGCApplication.h"
27 28 29 30 31 32 33

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

#include <string.h>

34
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
Don Gagne's avatar
Don Gagne committed
35
QGC_LOGGING_CATEGORY(MockLinkVerboseLog, "MockLinkVerboseLog")
36

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

Don Gagne's avatar
Don Gagne committed
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 70
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
71 72
float MockLink::_vehicleLatitude =  47.633033f;
float MockLink::_vehicleLongitude = -122.08794f;
Don Gagne's avatar
Don Gagne committed
73
float MockLink::_vehicleAltitude =  3.5f;
Don Gagne's avatar
Don Gagne committed
74

75
const char* MockConfiguration::_firmwareTypeKey =   "FirmwareType";
76
const char* MockConfiguration::_vehicleTypeKey =    "VehicleType";
77
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
78

79
MockLink::MockLink(MockConfiguration* config)
80
    : _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol())
81 82 83 84 85
    , _name("MockLink")
    , _connected(false)
    , _vehicleSystemId(128)     // FIXME: Pull from eventual parameter manager
    , _vehicleComponentId(200)  // FIXME: magic number?
    , _inNSH(false)
Don Gagne's avatar
Don Gagne committed
86
    , _mavlinkStarted(true)
87 88
    , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState(MAV_STATE_STANDBY)
Don Gagne's avatar
Don Gagne committed
89
    , _firmwareType(MAV_AUTOPILOT_PX4)
90
    , _vehicleType(MAV_TYPE_QUADROTOR)
91
    , _fileServer(NULL)
92
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
93
    , _apmSendHomePositionOnEmptyList(false)
94
    , _sendHomePositionDelayCount(2)
95
{
96
    _config = config;
97
    if (_config) {
Don Gagne's avatar
Don Gagne committed
98
        _firmwareType = config->firmwareType();
99
        _vehicleType = config->vehicleType();
100
        _sendStatusText = config->sendStatusText();
Don Gagne's avatar
Don Gagne committed
101
        _config->setLink(this);
102 103
    }

Don Gagne's avatar
Don Gagne committed
104 105 106 107 108 109
    union px4_custom_mode   px4_cm;

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

110 111
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
dogmaphobic's avatar
dogmaphobic committed
112

113
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
114

115 116 117 118 119 120
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
121
    _disconnect();
122 123 124 125 126 127 128
}

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

129
bool MockLink::_connect(void)
130
{
131 132 133 134 135
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
136

137 138 139
    return true;
}

Don Gagne's avatar
Don Gagne committed
140
void MockLink::_disconnect(void)
141
{
142 143
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
144 145
        quit();
        wait();
146 147
        emit disconnected();
    }
148 149 150 151 152 153 154
}

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

dogmaphobic's avatar
dogmaphobic committed
156
    QObject::connect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
157 158
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
159

160 161 162
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
163

164
    exec();
165

dogmaphobic's avatar
dogmaphobic committed
166
    QObject::disconnect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
167 168
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
dogmaphobic's avatar
dogmaphobic committed
169

170
    _missionItemHandler.shutdown();
171 172 173 174
}

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

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

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

void MockLink::_loadParams(void)
{
205 206 207 208 209 210 211 212 213 214 215 216
    QFile paramFile;

    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        if (_vehicleType == MAV_TYPE_FIXED_WING) {
            paramFile.setFileName(":/unittest/APMArduPlaneMockLink.params");
        } else {
            paramFile.setFileName(":/unittest/APMArduCopterMockLink.params");
        }
    } else {
        paramFile.setFileName(":/unittest/PX4MockLink.params");
    }

217

218 219 220
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
221

222
    QTextStream paramStream(&paramFile);
223

224 225
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
226

227 228 229
        if (line.startsWith("#")) {
            continue;
        }
230

231 232
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
233

234
        int componentId = paramData.at(1).toInt();
235 236 237
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
238

239 240 241 242 243 244 245 246 247 248 249
        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;
250 251 252 253 254 255 256 257 258
            case MAV_PARAM_TYPE_UINT16:
                paramValue = QVariant((quint16)valStr.toUInt());
                break;
            case MAV_PARAM_TYPE_INT16:
                paramValue = QVariant((qint16)valStr.toInt());
                break;
            case MAV_PARAM_TYPE_UINT8:
                paramValue = QVariant((quint8)valStr.toUInt());
                break;
259
            case MAV_PARAM_TYPE_INT8:
260
                paramValue = QVariant((qint8)valStr.toUInt());
261 262
                break;
            default:
263 264
                qCritical() << "Unknown type" << paramType;
                paramValue = QVariant(valStr.toInt());
265 266
                break;
        }
267

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

270
        _mapParamName2Value[componentId][paramName] = paramValue;
271
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
272 273 274 275 276 277 278 279 280 281
    }
}

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
Don Gagne's avatar
Don Gagne committed
282
                               _vehicleType,        // MAV_TYPE
Don Gagne's avatar
Don Gagne committed
283
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
284 285
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
286
                               _mavState);          // MAV_STATE
dogmaphobic's avatar
dogmaphobic committed
287

288 289
    respondWithMavlinkMessage(msg);
}
290

291 292 293
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
294

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

306 307 308 309 310 311 312 313 314 315 316 317 318
    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);
        }
319

320 321 322 323 324 325 326 327
        _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);
328

329 330 331 332 333 334 335 336
    // 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;
337

Don Gagne's avatar
Don Gagne committed
338 339
#if 0
        // MockLink not quite ready to handle this correctly yet
340 341 342 343
        if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
            // This is the mavlink start command
            _mavlinkStarted = true;
        }
Don Gagne's avatar
Don Gagne committed
344
#endif
345 346 347 348 349 350 351 352
    }
}

/// @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;
353

354 355
    for (qint64 i=0; i<cBytes; i++)
    {
356
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
357 358
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
359

360
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
361 362
            continue;
        }
363

364 365 366 367
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
368

369 370 371
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
372

373 374 375
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
376

377 378 379
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
380

381 382 383
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
384

385 386 387
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
388

389 390 391
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
392

Don Gagne's avatar
Don Gagne committed
393 394 395 396
            case MAVLINK_MSG_ID_MANUAL_CONTROL:
                _handleManualControl(msg);
                break;

397 398 399 400 401 402 403 404 405
            default:
                break;
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
406
    qCDebug(MockLinkLog) << "Heartbeat";
407 408 409 410 411 412
}

void MockLink::_handleSetMode(const mavlink_message_t& msg)
{
    mavlink_set_mode_t request;
    mavlink_msg_set_mode_decode(&msg, &request);
413

414
    Q_ASSERT(request.target_system == _vehicleSystemId);
415

416 417 418 419
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
420 421 422 423 424 425 426 427
void MockLink::_handleManualControl(const mavlink_message_t& msg)
{
    mavlink_manual_control_t manualControl;
    mavlink_msg_manual_control_decode(&msg, &manualControl);

    qDebug() << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
}

428
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
429 430
{
    mavlink_param_union_t   valueUnion;
431

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

436
    valueUnion.param_float = paramFloat;
437

438
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
439

440
    QVariant paramVariant;
441

442
    switch (paramType) {
443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474
    case MAV_PARAM_TYPE_REAL32:
        paramVariant = QVariant::fromValue(valueUnion.param_float);
        break;

    case MAV_PARAM_TYPE_UINT32:
        paramVariant = QVariant::fromValue(valueUnion.param_uint32);
        break;

    case MAV_PARAM_TYPE_INT32:
        paramVariant = QVariant::fromValue(valueUnion.param_int32);
        break;

    case MAV_PARAM_TYPE_UINT16:
        paramVariant = QVariant::fromValue(valueUnion.param_uint16);
        break;

    case MAV_PARAM_TYPE_INT16:
        paramVariant = QVariant::fromValue(valueUnion.param_int16);
        break;

    case MAV_PARAM_TYPE_UINT8:
        paramVariant = QVariant::fromValue(valueUnion.param_uint8);
        break;

    case MAV_PARAM_TYPE_INT8:
        paramVariant = QVariant::fromValue(valueUnion.param_int8);
        break;

    default:
        qCritical() << "Invalid parameter type" << paramType;
        paramVariant = QVariant::fromValue(valueUnion.param_int32);
        break;
475
    }
476

477
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
478
    _mapParamName2Value[componentId][paramName] = paramVariant;
479 480
}

481
/// Convert from a parameter variant to the float value from mavlink_param_union_t
482
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
483
{
484
    mavlink_param_union_t   valueUnion;
485

486 487
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
488
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
489

490
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
491
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
492

493
    switch (paramType) {
494 495 496
    case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
        break;
497

498 499 500 501 502 503 504
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
505

506 507 508 509 510 511 512
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
513

514 515 516 517 518 519 520
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
521

522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552
    case MAV_PARAM_TYPE_INT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int16 = paramVar.toInt();
        }
        break;

    case MAV_PARAM_TYPE_UINT8:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint8 = paramVar.toUInt();
        }
        break;

    case MAV_PARAM_TYPE_INT8:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
        } else {
            valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
        }
        break;

    default:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        qCritical() << "Invalid parameter type" << paramType;
553
    }
554

555
    return valueUnion.param_float;
556 557 558 559 560
}

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

562
    mavlink_msg_param_request_list_decode(&msg, &request);
563

564
    Q_ASSERT(request.target_system == _vehicleSystemId);
565
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
566

567 568
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
569 570

    foreach (int componentId, _mapParamName2Value.keys()) {
571
        uint16_t paramIndex = 0;
572
        int cParameters = _mapParamName2Value[componentId].count();
dogmaphobic's avatar
dogmaphobic committed
573

574
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
575 576 577 578 579 580 581 582 583 584 585
            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);

586
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
587 588 589 590 591 592 593 594 595

            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
596
            respondWithMavlinkMessage(responseMsg);
dogmaphobic's avatar
dogmaphobic committed
597

598 599 600 601
            // Only first parameter the first time through
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
602

603 604 605 606
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
dogmaphobic's avatar
dogmaphobic committed
607

608
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
609 610
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
611
                skipParam = false;
612 613 614 615
                paramIndex++;
            } else {
                char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
                mavlink_message_t       responseMsg;
dogmaphobic's avatar
dogmaphobic committed
616

617 618
                Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
                Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic's avatar
dogmaphobic committed
619

620
                MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
dogmaphobic's avatar
dogmaphobic committed
621

622 623
                Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
                strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
dogmaphobic's avatar
dogmaphobic committed
624

625
                qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
dogmaphobic's avatar
dogmaphobic committed
626

627 628 629 630 631 632 633 634
                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
635
                respondWithMavlinkMessage(responseMsg);
636
            }
637
        }
638 639 640 641 642 643 644
    }
}

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

646
    Q_ASSERT(request.target_system == _vehicleSystemId);
647
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
648

649 650
    // 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
651
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
652
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
653

Don Gagne's avatar
Don Gagne committed
654
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
dogmaphobic's avatar
dogmaphobic committed
655

656 657
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
658
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
659

660
    // Save the new value
661
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
662

663 664 665
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
666 667 668 669 670 671 672
                                 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
673
    respondWithMavlinkMessage(responseMsg);
674 675 676 677
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
678
    mavlink_message_t   responseMsg;
679 680
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
681 682

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
683
    int componentId = request.target_component;
684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702

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

703
    Q_ASSERT(_mapParamName2Value.contains(componentId));
704

705 706
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
707

708
    Q_ASSERT(request.target_system == _vehicleSystemId);
709

710 711 712
    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);
713
    } else {
714
        // Request is by index
715

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

718
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
719 720
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
721
    }
722

723
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
724
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
725

726
    mavlink_msg_param_value_pack(_vehicleSystemId,
727 728 729 730 731 732 733
                                 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
734
    respondWithMavlinkMessage(responseMsg);
735 736
}

737 738 739
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
740

741 742 743 744
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
745

746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770
    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
771 772 773 774 775 776 777
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
778
}
779 780 781 782

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
    mavlink_command_long_t request;
dogmaphobic's avatar
dogmaphobic committed
783

784 785 786 787 788 789 790 791 792 793 794
    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;
        }
    }
}

795
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
796
{
797
    _missionItemHandler.setMissionItemFailureMode(failureMode);
798
}
799 800 801

void MockLink::_sendHomePosition(void)
{
802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821
    // 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],
dogmaphobic's avatar
dogmaphobic committed
822
                                       0.0f, 0.0f, 0.0f);
823 824
        respondWithMavlinkMessage(msg);
    }
825
}
Don Gagne's avatar
Don Gagne committed
826 827 828 829 830 831 832 833 834 835 836

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
dogmaphobic's avatar
dogmaphobic committed
837
                                 (int32_t)(_vehicleLatitude  * 1E7),
Don Gagne's avatar
Don Gagne committed
838
                                 (int32_t)(_vehicleLongitude * 1E7),
dogmaphobic's avatar
dogmaphobic committed
839
                                 (int32_t)(_vehicleAltitude  * 1000),
Don Gagne's avatar
Don Gagne committed
840 841 842 843 844 845
                                 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);
}
846

847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878
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);
    }
}

879 880 881
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
882
    , _vehicleType(MAV_TYPE_QUADROTOR)
883
    , _sendStatusText(false)
884 885 886 887 888 889 890
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
891
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
892
    _vehicleType =      source->_vehicleType;
893
    _sendStatusText =   source->_sendStatusText;
894 895 896 897 898 899
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
900 901 902 903 904 905 906

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

    _firmwareType =     usource->_firmwareType;
907
    _vehicleType =      usource->_vehicleType;
908
    _sendStatusText =   usource->_sendStatusText;
909 910 911 912 913 914
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
915
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
916
    settings.setValue(_sendStatusTextKey, _sendStatusText);
917 918 919 920 921 922 923 924
    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();
925
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
926
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
927 928 929 930 931 932 933 934 935
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
936
            qWarning() << "updateSettings not supported";
937 938 939 940
            //ulink->_restartConnection();
        }
    }
}
941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995

MockLink*  MockLink::_startMockLink(MockConfiguration* mockConfig)
{
    LinkManager* linkManager = qgcApp()->toolbox()->linkManager();

    mockConfig->setDynamic(true);
    linkManager->linkConfigurations()->append(mockConfig);

    return qobject_cast<MockLink*>(linkManager->createConnectedLink(mockConfig));
}

MockLink*  MockLink::startPX4MockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("PX4 MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_PX4);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startGenericMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("Generic MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}

MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
    mockConfig->setSendStatusText(sendStatusText);

    return _startMockLink(mockConfig);
}