MockLink.cc 32.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 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 73 74
float MockLink::_vehicleLatitude =  47.633033f;
float MockLink::_vehicleLongitude = -122.08794f;
float MockLink::_vehicleAltitude =  2.5f;

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 86 87 88
    , _name("MockLink")
    , _connected(false)
    , _vehicleSystemId(128)     // FIXME: Pull from eventual parameter manager
    , _vehicleComponentId(200)  // FIXME: magic number?
    , _inNSH(false)
    , _mavlinkStarted(false)
    , _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
    , _mavState(MAV_STATE_STANDBY)
Don Gagne's avatar
Don Gagne committed
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();
101 102
    }

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

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

109 110 111
    _fileServer = new MockLinkFileServer(_vehicleSystemId, _vehicleComponentId, this);
    Q_CHECK_PTR(_fileServer);
    
112
    moveToThread(this);
113
    
114 115 116 117 118 119
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

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

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

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

136 137 138
    return true;
}

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

148 149 150 151 152 153 154 155
    return true;
}

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

157 158 159
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
160

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

165
    exec();
166

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

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

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

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

void MockLink::_loadParams(void)
{
206 207 208 209 210 211 212 213 214 215 216 217
    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");
    }

218

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

223
    QTextStream paramStream(&paramFile);
224

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

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

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

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

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

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

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

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

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
Don Gagne's avatar
Don Gagne committed
284
                               _firmwareType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
285 286
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
287
                               _mavState);          // MAV_STATE
288 289 290
    
    respondWithMavlinkMessage(msg);
}
291

292 293 294 295
void MockLink::respondWithMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    
296 297 298 299 300 301 302 303 304 305
    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);
306

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

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

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

339 340 341 342 343 344 345 346 347 348 349 350
        if (strncmp(bytes, "sh /etc/init.d/rc.usb\n", cBytes) == 0) {
            // This is the mavlink start command
            _mavlinkStarted = true;
        }
    }
}

/// @brief Handle incoming bytes which are meant to be handled by the mavlink protocol
void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
{
    mavlink_message_t msg;
    mavlink_status_t comm;
351

352 353
    for (qint64 i=0; i<cBytes; i++)
    {
354
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
355 356
            continue;
        }
Don Gagne's avatar
Don Gagne committed
357
        
358
        if (_missionItemHandler.handleMessage(msg)) {
Don Gagne's avatar
Don Gagne committed
359 360
            continue;
        }
361

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

367 368 369
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
370

371 372 373
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
374

375 376 377
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
378

379 380 381
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
382 383 384 385
                
            case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
                _handleFTP(msg);
                break;
386 387 388 389
                
            case MAVLINK_MSG_ID_COMMAND_LONG:
                _handleCommandLong(msg);
                break;
390

391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409
            default:
                break;
        }
    }
}

void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
    Q_UNUSED(msg);
#if 0
    mavlink_heartbeat_t heartbeat;
    mavlink_msg_heartbeat_decode(&msg, &heartbeat);
#endif
}

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

411
    Q_ASSERT(request.target_system == _vehicleSystemId);
412

413 414 415 416
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

417
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
418 419
{
    mavlink_param_union_t   valueUnion;
420

421 422
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
423
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
424

425
    valueUnion.param_float = paramFloat;
426

427
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
428

429
    QVariant paramVariant;
430

431
    switch (paramType) {
432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463
    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;
464
    }
465

466
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
467
    _mapParamName2Value[componentId][paramName] = paramVariant;
468 469
}

470
/// Convert from a parameter variant to the float value from mavlink_param_union_t
471
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
472
{
473
    mavlink_param_union_t   valueUnion;
474

475 476
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
477
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
478

479
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
480
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
481

482
    switch (paramType) {
483 484 485
    case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
        break;
486

487 488 489 490 491 492 493
    case MAV_PARAM_TYPE_UINT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toUInt();
        } else {
            valueUnion.param_uint32 = paramVar.toUInt();
        }
        break;
494

495 496 497 498 499 500 501
    case MAV_PARAM_TYPE_INT32:
        if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            valueUnion.param_float = paramVar.toInt();
        } else {
            valueUnion.param_int32 = paramVar.toInt();
        }
        break;
502

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

511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541
    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;
542
    }
543

544
    return valueUnion.param_float;
545 546 547 548 549
}

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

551
    mavlink_msg_param_request_list_decode(&msg, &request);
552

553
    Q_ASSERT(request.target_system == _vehicleSystemId);
554
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);
555 556 557
    
    // We must send the first parameter for each component first. Otherwise system won't correctly know
    // when all parameters are loaded.
558 559

    foreach (int componentId, _mapParamName2Value.keys()) {
560
        uint16_t paramIndex = 0;
561 562 563 564 565 566 567 568 569 570 571 572 573 574
        int cParameters = _mapParamName2Value[componentId].count();
        
        foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
            char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
            mavlink_message_t       responseMsg;

            Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
            Q_ASSERT(_mapParamName2MavParamType.contains(paramName));

            MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];

            Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
            strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);

575
            qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
576 577 578 579 580 581 582 583 584

            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
585
            respondWithMavlinkMessage(responseMsg);
586 587 588 589 590 591 592 593 594 595 596 597 598 599
            
            // Only first parameter the first time through
            break;
        }
    }
    
    foreach (int componentId, _mapParamName2Value.keys()) {
        uint16_t paramIndex = 0;
        int cParameters = _mapParamName2Value[componentId].count();
        bool skipParam = true;
        
        foreach(QString paramName, _mapParamName2Value[componentId].keys()) {
            if (skipParam) {
                // We've already sent the first param
Don Gagne's avatar
Don Gagne committed
600
                skipParam = false;
601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623
                paramIndex++;
            } else {
                char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
                mavlink_message_t       responseMsg;
                
                Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
                Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
                
                MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
                
                Q_ASSERT(paramName.length() <= MAVLINK_MSG_ID_PARAM_VALUE_LEN);
                strncpy(paramId, paramName.toLocal8Bit().constData(), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
                
                qCDebug(MockLinkLog) << "Sending msg_param_value" << componentId << paramId << paramType << _mapParamName2Value[componentId][paramId];
                
                mavlink_msg_param_value_pack(_vehicleSystemId,
                                             componentId,                       // component id
                                             &responseMsg,                      // Outgoing message
                                             paramId,                           // Parameter name
                                             _floatUnionForParam(componentId, paramName),    // Parameter value
                                             paramType,                         // MAV_PARAM_TYPE
                                             cParameters,                       // Total number of parameters
                                             paramIndex++);                     // Index of this parameter
624
                respondWithMavlinkMessage(responseMsg);
625
            }
626
        }
627 628 629 630 631 632 633
    }
}

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

635
    Q_ASSERT(request.target_system == _vehicleSystemId);
636
    int componentId = request.target_component;
Don Gagne's avatar
Don Gagne committed
637
    
638 639
    // 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
640
    paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN] = 0;
641
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
642

Don Gagne's avatar
Don Gagne committed
643 644
    qCDebug(MockLinkLog) << "_handleParamSet" << componentId << paramId << request.param_type;
    
645 646
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
647
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
648

649
    // Save the new value
650
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
651

652 653 654
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
655 656 657 658 659 660 661
                                 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
662
    respondWithMavlinkMessage(responseMsg);
663 664 665 666
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
667
    mavlink_message_t   responseMsg;
668 669
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
670 671

    const QString param_name(QString::fromLocal8Bit(request.param_id, strnlen(request.param_id, MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)));
672
    int componentId = request.target_component;
673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691

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

692
    Q_ASSERT(_mapParamName2Value.contains(componentId));
693

694 695
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
696

697
    Q_ASSERT(request.target_system == _vehicleSystemId);
698

699 700 701
    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);
702
    } else {
703
        // Request is by index
704

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

707
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
708 709
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
710
    }
711

712
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
713
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
714

715
    mavlink_msg_param_value_pack(_vehicleSystemId,
716 717 718 719 720 721 722
                                 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
723
    respondWithMavlinkMessage(responseMsg);
724 725
}

726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759
void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
{
    uint16_t chanRaw[18];
    
    for (int i=0; i<18; i++) {
        chanRaw[i] = UINT16_MAX;
    }
    chanRaw[channel] = raw;
    
    mavlink_message_t responseMsg;
    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &responseMsg,          // Outgoing message
                                 0,                     // time since boot, ignored
                                 18,                    // channel count
                                 chanRaw[0],            // channel raw value
                                 chanRaw[1],            // channel raw value
                                 chanRaw[2],            // channel raw value
                                 chanRaw[3],            // channel raw value
                                 chanRaw[4],            // channel raw value
                                 chanRaw[5],            // channel raw value
                                 chanRaw[6],            // channel raw value
                                 chanRaw[7],            // channel raw value
                                 chanRaw[8],            // channel raw value
                                 chanRaw[9],            // channel raw value
                                 chanRaw[10],           // channel raw value
                                 chanRaw[11],           // channel raw value
                                 chanRaw[12],           // channel raw value
                                 chanRaw[13],           // channel raw value
                                 chanRaw[14],           // channel raw value
                                 chanRaw[15],           // channel raw value
                                 chanRaw[16],           // channel raw value
                                 chanRaw[17],           // channel raw value
                                 0);                    // rss
760 761 762 763 764 765 766
    respondWithMavlinkMessage(responseMsg);
}

void MockLink::_handleFTP(const mavlink_message_t& msg)
{
    Q_ASSERT(_fileServer);
    _fileServer->handleFTPMessage(msg);
767
}
768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783

void MockLink::_handleCommandLong(const mavlink_message_t& msg)
{
    mavlink_command_long_t request;
    
    mavlink_msg_command_long_decode(&msg, &request);

    if (request.command == MAV_CMD_COMPONENT_ARM_DISARM) {
        if (request.param1 == 0.0f) {
            _mavBaseMode &= ~MAV_MODE_FLAG_SAFETY_ARMED;
        } else {
            _mavBaseMode |= MAV_MODE_FLAG_SAFETY_ARMED;
        }
    }
}

784 785 786 787
void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode_t failureMode, bool firstTimeOnly)
{
    _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
}
788 789 790

void MockLink::_sendHomePosition(void)
{
791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813
    // APM stack does not yet support HOME_POSITION

    if (_firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {

        mavlink_message_t msg;

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

        mavlink_msg_home_position_pack(_vehicleSystemId,
                                       _vehicleComponentId,
                                       &msg,
                                       (int32_t)(_vehicleLatitude * 1E7),
                                       (int32_t)(_vehicleLongitude * 1E7),
                                       (int32_t)(_vehicleAltitude * 1000),
                                       0.0f, 0.0f, 0.0f,
                                       &bogus[0],
                0.0f, 0.0f, 0.0f);
        respondWithMavlinkMessage(msg);
    }
814
}
Don Gagne's avatar
Don Gagne committed
815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834

void MockLink::_sendGpsRawInt(void)
{
    static uint64_t timeTick = 0;
    mavlink_message_t msg;

    mavlink_msg_gps_raw_int_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &msg,
                                 timeTick++,                            // time since boot
                                 3,                                     // 3D fix
                                 (int32_t)(_vehicleLatitude * 1E7),
                                 (int32_t)(_vehicleLongitude * 1E7),
                                 (int32_t)(_vehicleAltitude * 1000),
                                 UINT16_MAX, UINT16_MAX,                // HDOP/VDOP not known
                                 UINT16_MAX,                            // velocity not known
                                 UINT16_MAX,                            // course over ground not known
                                 8);                                    // satellite count
    respondWithMavlinkMessage(msg);
}
835

836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867
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);
    }
}

868 869 870
MockConfiguration::MockConfiguration(const QString& name)
    : LinkConfiguration(name)
    , _firmwareType(MAV_AUTOPILOT_PX4)
871
    , _vehicleType(MAV_TYPE_QUADROTOR)
872
    , _sendStatusText(false)
873 874 875 876 877 878 879
{

}

MockConfiguration::MockConfiguration(MockConfiguration* source)
    : LinkConfiguration(source)
{
880
    _firmwareType =     source->_firmwareType;
881
    _vehicleType =       source->_vehicleType;
882
    _sendStatusText =   source->_sendStatusText;
883 884 885 886 887 888
}

void MockConfiguration::copyFrom(LinkConfiguration *source)
{
    LinkConfiguration::copyFrom(source);
    MockConfiguration* usource = dynamic_cast<MockConfiguration*>(source);
889 890 891 892 893 894 895

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

    _firmwareType =     usource->_firmwareType;
896
    _vehicleType =      usource->_vehicleType;
897
    _sendStatusText =   usource->_sendStatusText;
898 899 900 901 902 903
}

void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
{
    settings.beginGroup(root);
    settings.setValue(_firmwareTypeKey, (int)_firmwareType);
904
    settings.setValue(_vehicleTypeKey, (int)_vehicleType);
905
    settings.setValue(_sendStatusTextKey, _sendStatusText);
906 907 908 909 910 911 912 913
    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();
914
    _vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
915
    _sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
916 917 918 919 920 921 922 923 924
    settings.endGroup();
}

void MockConfiguration::updateSettings()
{
    if (_link) {
        MockLink* ulink = dynamic_cast<MockLink*>(_link);
        if (ulink) {
            // Restart connect not supported
925
            qWarning() << "updateSettings not supported";
926 927 928 929
            //ulink->_restartConnection();
        }
    }
}