MockLink.cc 34.8 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
bool MockLink::_connect(void)
125
{
126 127 128 129 130
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
131

132 133 134
    return true;
}

Don Gagne's avatar
Don Gagne committed
135
void MockLink::_disconnect(void)
136
{
137 138
    if (_connected) {
        _connected = false;
Daniel Agar's avatar
Daniel Agar committed
139 140
        quit();
        wait();
141 142
        emit disconnected();
    }
143 144 145 146 147 148 149
}

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

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

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

159
    exec();
160

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

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

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

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

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

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

213

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

218
    QTextStream paramStream(&paramFile);
219

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

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

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

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

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

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

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

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

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

284 285
    respondWithMavlinkMessage(msg);
}
286

Don Gagne's avatar
Don Gagne committed
287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304
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);
}

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

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

320 321 322 323 324 325 326 327 328 329 330 331 332
    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);
        }
333

334 335 336 337 338 339 340 341
        _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);
342

343 344 345 346 347 348 349 350
    // 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;
351

Don Gagne's avatar
Don Gagne committed
352 353
#if 0
        // MockLink not quite ready to handle this correctly yet
354 355 356 357
        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
358
#endif
359 360 361 362 363 364 365 366
    }
}

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

368 369
    for (qint64 i=0; i<cBytes; i++)
    {
370
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
371 372
            continue;
        }
dogmaphobic's avatar
dogmaphobic committed
373

374
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
375 376
            continue;
        }
377

378 379 380 381
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
382

383 384 385
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
386

387 388 389
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
390

391 392 393
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
394

395 396 397
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
398

399 400 401
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
dogmaphobic's avatar
dogmaphobic committed
402

403 404 405
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
406

Don Gagne's avatar
Don Gagne committed
407 408 409 410
            case MAVLINK_MSG_ID_MANUAL_CONTROL:
                _handleManualControl(msg);
                break;

411 412 413 414 415 416 417 418 419
            default:
                break;
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
420
    qCDebug(MockLinkLog) << "Heartbeat";
421 422 423 424 425 426
}

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

428
    Q_ASSERT(request.target_system == _vehicleSystemId);
429

430 431 432 433
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

Don Gagne's avatar
Don Gagne committed
434 435 436 437 438 439 440 441
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;
}

442
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
443 444
{
    mavlink_param_union_t   valueUnion;
445

446 447
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
448
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
449

450
    valueUnion.param_float = paramFloat;
451

452
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
453

454
    QVariant paramVariant;
455

456
    switch (paramType) {
457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488
    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;
489
    }
490

491
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
492
    _mapParamName2Value[componentId][paramName] = paramVariant;
493 494
}

495
/// Convert from a parameter variant to the float value from mavlink_param_union_t
496
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
497
{
498
    mavlink_param_union_t   valueUnion;
499

500 501
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
502
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
503

504
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
505
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
506

507
    switch (paramType) {
508 509 510
    case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
        break;
511

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

520 521 522 523 524 525 526
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
527

528 529 530 531 532 533 534
    case MAV_PARAM_TYPE_UINT16:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint16 = paramVar.toUInt();
        }
        break;
535

536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566
    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;
567
    }
568

569
    return valueUnion.param_float;
570 571 572 573 574
}

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

576
    mavlink_msg_param_request_list_decode(&msg, &request);
577

578
    Q_ASSERT(request.target_system == _vehicleSystemId);
579
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
dogmaphobic's avatar
dogmaphobic committed
580

581 582
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
583 584

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

588
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
589 590 591 592 593 594 595 596 597 598 599
            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);

600
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
601 602 603 604 605 606 607 608 609

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

612 613 614 615
            // Only first parameter the first time through
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
616

617 618 619 620
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
dogmaphobic's avatar
dogmaphobic committed
621

622
        foreach(const QString &paramName, _mapParamName2Value[componentId].keys()) {
623 624
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
625
                skipParam = false;
626 627 628 629
                paramIndex++;
            } else {
                char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
                mavlink_message_t       responseMsg;
dogmaphobic's avatar
dogmaphobic committed
630

631 632
                Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
                Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
dogmaphobic's avatar
dogmaphobic committed
633

634
                MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
dogmaphobic's avatar
dogmaphobic committed
635

636 637
                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
638

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

641 642 643 644 645 646 647 648
                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
649
                respondWithMavlinkMessage(responseMsg);
650
            }
651
        }
652 653 654 655 656 657 658
    }
}

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

660
    Q_ASSERT(request.target_system == _vehicleSystemId);
661
    int componentId = request.target_component;
dogmaphobic's avatar
dogmaphobic committed
662

663 664
    // 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
665
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
666
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
667

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

670 671
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
672
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
673

674
    // Save the new value
675
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
676

677 678 679
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
680 681 682 683 684 685 686
                                 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
687
    respondWithMavlinkMessage(responseMsg);
688 689 690 691
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
692
    mavlink_message_t   responseMsg;
693 694
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
695 696

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
697
    int componentId = request.target_component;
698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716

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

717
    Q_ASSERT(_mapParamName2Value.contains(componentId));
718

719 720
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
721

722
    Q_ASSERT(request.target_system == _vehicleSystemId);
723

724 725 726
    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);
727
    } else {
728
        // Request is by index
729

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

732
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
733 734
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
735
    }
736

737
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
738
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
739

740
    mavlink_msg_param_value_pack(_vehicleSystemId,
741 742 743 744 745 746 747
                                 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
748
    respondWithMavlinkMessage(responseMsg);
749 750
}

751 752 753
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
dogmaphobic's avatar
dogmaphobic committed
754

755 756 757 758
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
dogmaphobic's avatar
dogmaphobic committed
759

760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784
    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
785 786 787 788 789 790 791
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
792
}
793 794 795 796

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

798 799 800 801 802 803 804 805 806 807 808
    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;
        }
    }
}

809
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode)
810
{
811
    _missionItemHandler.setMissionItemFailureMode(failureMode);
812
}
813 814 815

void MockLink::_sendHomePosition(void)
{
816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833
    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);
834
}
Don Gagne's avatar
Don Gagne committed
835 836 837 838 839 840 841 842 843 844 845

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
846
                                 (int32_t)(_vehicleLatitude  * 1E7),
Don Gagne's avatar
Don Gagne committed
847
                                 (int32_t)(_vehicleLongitude * 1E7),
dogmaphobic's avatar
dogmaphobic committed
848
                                 (int32_t)(_vehicleAltitude  * 1000),
Don Gagne's avatar
Don Gagne committed
849 850 851 852 853 854
                                 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);
}
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 880 881 882 883 884 885 886 887
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);
    }
}

888 889 890
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
891
    , _vehicleType(MAV_TYPE_QUADROTOR)
892
    , _sendStatusText(false)
893 894 895 896 897 898 899
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
900
    _firmwareType =     source->_firmwareType;
dogmaphobic's avatar
dogmaphobic committed
901
    _vehicleType =      source->_vehicleType;
902
    _sendStatusText =   source->_sendStatusText;
903 904 905 906 907 908
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
909 910 911 912 913 914 915

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

    _firmwareType =     usource->_firmwareType;
916
    _vehicleType =      usource->_vehicleType;
917
    _sendStatusText =   usource->_sendStatusText;
918 919 920 921 922 923
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
924
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
925
    settings.setValue(_sendStatusTextKey, _sendStatusText);
926 927 928 929 930 931 932 933
    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();
934
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
935
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
936 937 938 939 940 941 942 943 944
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
945
            qWarning() << "updateSettings not supported";
946 947 948 949
            //ulink->_restartConnection();
        }
    }
}
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 997 998 999 1000 1001 1002 1003 1004

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