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

3
 QGroundControl Open Source Ground Control Station
4

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

7
 This file is part of the QGROUNDCONTROL project
8

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

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

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

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

#include "MockLink.h"
25
#include "QGCLoggingCategory.h"
26
#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
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,
49 50
    PX4_CUSTOM_MAIN_MODE_STABILIZED,
    PX4_CUSTOM_MAIN_MODE_RATTITUDE
Don Gagne's avatar
Don Gagne committed
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
};

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

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

81
MockLink::MockLink(MockConfiguration* config)
82
    : _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol())
83 84 85 86 87
    , _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
88
    , _mavlinkStarted(true)
89 90
    , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState(MAV_STATE_STANDBY)
Don Gagne's avatar
Don Gagne committed
91
    , _firmwareType(MAV_AUTOPILOT_PX4)
92
    , _vehicleType(MAV_TYPE_QUADROTOR)
93
    , _fileServer(NULL)
94
    , _sendStatusText(false)
Don Gagne's avatar
Don Gagne committed
95
    , _apmSendHomePositionOnEmptyList(false)
96
    , _sendHomePositionDelayCount(2)
97
{
98
    _config = config;
99
    if (_config) {
Don Gagne's avatar
Don Gagne committed
100
        _firmwareType = config->firmwareType();
101
        _vehicleType = config->vehicleType();
102
        _sendStatusText = config->sendStatusText();
Don Gagne's avatar
Don Gagne committed
103
        _config->setLink(this);
104 105
    }

Don Gagne's avatar
Don Gagne committed
106 107 108 109 110 111
    union px4_custom_mode   px4_cm;

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

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

115
    moveToThread(this);
dogmaphobic's avatar
dogmaphobic committed
116

117 118 119 120 121
    _loadParams();
}

MockLink::~MockLink(void)
{
122
    _disconnect();
123 124
}

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

133 134 135
    return true;
}

Don Gagne's avatar
Don Gagne committed
136
void 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
}

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

dogmaphobic's avatar
dogmaphobic committed
152
    QObject::connect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
153 154
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
155

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

160
    exec();
161

dogmaphobic's avatar
dogmaphobic committed
162
    QObject::disconnect(&_timer1HzTasks,  &QTimer::timeout, this, &MockLink::_run1HzTasks);
163 164
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
dogmaphobic's avatar
dogmaphobic committed
165

166
    _missionItemHandler.shutdown();
167 168 169 170
}

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

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

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

void MockLink::_loadParams(void)
{
202 203 204 205 206 207 208 209 210 211 212 213
    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");
    }

214

215 216 217
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
218

219
    QTextStream paramStream(&paramFile);
220

221 222
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
223

224 225 226
        if (line.startsWith("#")) {
            continue;
        }
227

228 229
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
230

231
        int componentId = paramData.at(1).toInt();
232 233 234
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
235

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

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

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

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

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

285 286
    respondWithMavlinkMessage(msg);
}
287

Don Gagne's avatar
Don Gagne committed
288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305
void MockLink::_sendVibration(void)
{
    mavlink_message_t   msg;

    mavlink_msg_vibration_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               0,       // time_usec
                               50.5,    // vibration_x,
                               10.5,    // vibration_y,
                               60.0,    // vibration_z,
                               1,       // clipping_0
                               2,       // clipping_0
                               3);      // clipping_0

    respondWithMavlinkMessage(msg);
}

306 307 308
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
dogmaphobic's avatar
dogmaphobic committed
309

310 311 312 313 314 315
    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
316
void MockLink::_writeBytes(const QByteArray bytes)
317 318 319 320 321 322 323 324
{
    if (_inNSH) {
        _handleIncomingNSHBytes(bytes.constData(), bytes.count());
    } else {
        if (bytes.startsWith(QByteArray("\r\r\r"))) {
            _inNSH  = true;
            _handleIncomingNSHBytes(&bytes.constData()[3], bytes.count() - 3);
        }
325

326 327 328 329 330 331 332 333
        _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);
334

335 336 337 338 339 340 341 342
    // 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;
343

Don Gagne's avatar
Don Gagne committed
344 345
#if 0
        // MockLink not quite ready to handle this correctly yet
346 347 348 349
        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
350
#endif
351 352 353 354 355 356 357 358
    }
}

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

360 361
    for (qint64 i=0; i<cBytes; i++)
    {
362
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
363 364
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
365

366
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
367 368
            continue;
        }
369

370 371 372 373
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
374

375 376 377
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
378

379 380 381
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
382

383 384 385
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
386

387 388 389
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
390

391 392 393
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
394

395 396 397
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
398

Don Gagne's avatar
Don Gagne committed
399 400 401 402
            case MAVLINK_MSG_ID_MANUAL_CONTROL:
                _handleManualControl(msg);
                break;

403 404 405 406 407 408 409 410 411
            default:
                break;
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
412
    qCDebug(MockLinkLog) << "Heartbeat";
413 414 415 416 417 418
}

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

420
    Q_ASSERT(request.target_system == _vehicleSystemId);
421

422 423 424 425
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
426 427 428 429 430 431 432 433
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;
}

434
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
435 436
{
    mavlink_param_union_t   valueUnion;
437

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

442
    valueUnion.param_float = paramFloat;
443

444
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
445

446
    QVariant paramVariant;
447

448
    switch (paramType) {
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 475 476 477 478 479 480
    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;
481
    }
482

483
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
484
    _mapParamName2Value[componentId][paramName] = paramVariant;
485 486
}

487
/// Convert from a parameter variant to the float value from mavlink_param_union_t
488
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
489
{
490
    mavlink_param_union_t   valueUnion;
491

492 493
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
494
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
495

496
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
497
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
498

499
    switch (paramType) {
500 501 502
    case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
        break;
503

504 505 506 507 508 509 510
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
511

512 513 514 515 516 517 518
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
519

520 521 522 523 524 525 526
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
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 553 554 555 556 557 558
    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;
559
    }
560

561
    return valueUnion.param_float;
562 563 564 565 566
}

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

568
    mavlink_msg_param_request_list_decode(&msg, &request);
569

570
    Q_ASSERT(request.target_system == _vehicleSystemId);
571
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
572

573 574
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
575 576

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

580
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
581 582 583 584 585 586 587 588 589 590 591
            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);

592
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
593 594 595 596 597 598 599 600 601

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

604 605 606 607
            // Only first parameter the first time through
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
608

609 610 611 612
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
dogmaphobic's avatar
dogmaphobic committed
613

614
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
615 616
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
617
                skipParam = false;
618 619 620 621
                paramIndex++;
            } else {
                char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
                mavlink_message_t       responseMsg;
dogmaphobic's avatar
dogmaphobic committed
622

623 624
                Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
                Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic's avatar
dogmaphobic committed
625

626
                MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
dogmaphobic's avatar
dogmaphobic committed
627

628 629
                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
630

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

633 634 635 636 637 638 639 640
                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
641
                respondWithMavlinkMessage(responseMsg);
642
            }
643
        }
644 645 646 647 648 649 650
    }
}

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

652
    Q_ASSERT(request.target_system == _vehicleSystemId);
653
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
654

655 656
    // 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
657
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
658
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
659

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

662 663
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
664
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
665

666
    // Save the new value
667
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
668

669 670 671
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
672 673 674 675 676 677 678
                                 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
679
    respondWithMavlinkMessage(responseMsg);
680 681 682 683
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
684
    mavlink_message_t   responseMsg;
685 686
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
687 688

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
689
    int componentId = request.target_component;
690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708

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

709
    Q_ASSERT(_mapParamName2Value.contains(componentId));
710

711 712
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
713

714
    Q_ASSERT(request.target_system == _vehicleSystemId);
715

716 717 718
    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);
719
    } else {
720
        // Request is by index
721

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

724
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
725 726
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
727
    }
728

729
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
730
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
731

732
    mavlink_msg_param_value_pack(_vehicleSystemId,
733 734 735 736 737 738 739
                                 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
740
    respondWithMavlinkMessage(responseMsg);
741 742
}

743 744 745
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
746

747 748 749 750
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
751

752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776
    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
777 778 779 780 781 782 783
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
784
}
785 786 787 788

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

790 791 792 793 794 795 796 797 798 799 800
    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;
        }
    }
}

801
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
802
{
803
    _missionItemHandler.setMissionItemFailureMode(failureMode);
804
}
805 806 807

void MockLink::_sendHomePosition(void)
{
808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825
    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);
826
}
Don Gagne's avatar
Don Gagne committed
827 828 829 830 831 832 833 834 835 836 837

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

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

}

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

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

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

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

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

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
937
            qWarning() << "updateSettings not supported";
938 939 940 941
            //ulink->_restartConnection();
        }
    }
}
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 996

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