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

3
 QGroundControl Open Source Ground Control Station
4

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

7
 This file is part of the QGROUNDCONTROL project
8

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

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

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

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

#include "MockLink.h"
25
#include "QGCLoggingCategory.h"
26 27 28 29 30 31 32

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

#include <string.h>

33
QGC_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")
34

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

Don Gagne's avatar
Don Gagne committed
40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68
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;
};

69
MockLink::MockLink(MockConfiguration* config) :
70 71 72 73 74 75
    _name("MockLink"),
    _connected(false),
    _vehicleSystemId(128),     // FIXME: Pull from eventual parameter manager
    _vehicleComponentId(200),  // FIXME: magic number?
    _inNSH(false),
    _mavlinkStarted(false),
Don Gagne's avatar
Don Gagne committed
76
    _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED),
77 78
    _mavState(MAV_STATE_STANDBY),
    _autopilotType(MAV_AUTOPILOT_PX4)
79
{
80
    _config = config;
Don Gagne's avatar
Don Gagne committed
81 82 83 84 85 86
    union px4_custom_mode   px4_cm;

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

87 88
    _missionItemHandler = new MockLinkMissionItemHandler(_vehicleSystemId, this);
    Q_CHECK_PTR(_missionItemHandler);
89

90 91 92 93 94 95 96
    moveToThread(this);
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

MockLink::~MockLink(void)
{
97
    _disconnect();
98 99 100 101 102 103 104
}

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

105
bool MockLink::_connect(void)
106
{
107 108 109 110 111
    if (!_connected) {
        _connected = true;
        start();
        emit connected();
    }
112

113 114 115
    return true;
}

116
bool MockLink::_disconnect(void)
117
{
118 119
    if (_connected) {
        _connected = false;
120
        exit();
121 122
        emit disconnected();
    }
123

124 125 126 127 128 129 130 131
    return true;
}

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

133 134 135
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
136

137 138 139
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
140

141
    exec();
142

143 144 145
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
146 147 148 149
}

void MockLink::_run1HzTasks(void)
{
150
    if (_mavlinkStarted && _connected) {
151 152 153 154 155 156
        _sendHeartBeat();
    }
}

void MockLink::_run10HzTasks(void)
{
157
    if (_mavlinkStarted && _connected) {
158 159 160 161 162
    }
}

void MockLink::_run50HzTasks(void)
{
163
    if (_mavlinkStarted && _connected) {
164 165 166 167 168 169
    }
}

void MockLink::_loadParams(void)
{
    QFile paramFile(":/unittest/MockLink.param");
170

171 172 173
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
174

175
    QTextStream paramStream(&paramFile);
176

177 178
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
179

180 181 182
        if (line.startsWith("#")) {
            continue;
        }
183

184 185
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
186

187
        int componentId = paramData.at(1).toInt();
188 189 190
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
191

192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209
        QVariant paramValue;
        switch (paramType) {
            case MAV_PARAM_TYPE_REAL32:
                paramValue = QVariant(valStr.toFloat());
                break;
            case MAV_PARAM_TYPE_UINT32:
                paramValue = QVariant(valStr.toUInt());
                break;
            case MAV_PARAM_TYPE_INT32:
                paramValue = QVariant(valStr.toInt());
                break;
            case MAV_PARAM_TYPE_INT8:
                paramValue = QVariant((unsigned char)valStr.toUInt());
                break;
            default:
                Q_ASSERT(false);
                break;
        }
210

Don Gagne's avatar
Don Gagne committed
211
        qCDebug(MockLinkLog) << "Loading param" << paramName << paramValue;
212

213
        _mapParamName2Value[componentId][paramName] = paramValue;
214
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
215 216 217 218 219 220 221 222 223 224 225 226
    }
}

void MockLink::_sendHeartBeat(void)
{
    mavlink_message_t   msg;
    uint8_t             buffer[MAVLINK_MAX_PACKET_LEN];

    mavlink_msg_heartbeat_pack(_vehicleSystemId,
                               _vehicleComponentId,
                               &msg,
                               MAV_TYPE_QUADROTOR,  // MAV_TYPE
227
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
228 229
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
230 231 232 233 234 235 236 237 238 239 240 241
                               _mavState);          // MAV_STATE

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

243 244 245 246 247 248 249 250 251 252 253 254 255
    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);
        }
256

257 258 259 260 261 262 263 264
        _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);
265

266 267 268 269 270 271 272 273
    // 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;
274

275 276 277 278 279 280 281 282 283 284 285 286
        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;
287

288 289
    for (qint64 i=0; i<cBytes; i++)
    {
290
        if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) {
291 292
            continue;
        }
293

294 295
        Q_ASSERT(_missionItemHandler);
        _missionItemHandler->handleMessage(msg);
296

297 298 299 300
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
301

302 303 304
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
305

306 307 308
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
309

310 311 312
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
313

314 315 316
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
317

318 319 320
            case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
                _handleMissionRequestList(msg);
                break;
321

322 323 324
            case MAVLINK_MSG_ID_MISSION_REQUEST:
                _handleMissionRequest(msg);
                break;
325

326 327 328
            case MAVLINK_MSG_ID_MISSION_ITEM:
                _handleMissionItem(msg);
                break;
329

330 331 332 333 334
#if 0
            case MAVLINK_MSG_ID_MISSION_COUNT:
                _handleMissionCount(msg);
                break;
#endif
335

336 337 338 339 340 341 342 343 344 345
            default:
                qDebug() << "MockLink: Unhandled mavlink message, id:" << msg.msgid;
                break;
        }
    }
}

void MockLink::_emitMavlinkMessage(const mavlink_message_t& msg)
{
    uint8_t outputBuffer[MAVLINK_MAX_PACKET_LEN];
346

347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364
    int cBuffer = mavlink_msg_to_send_buffer(outputBuffer, &msg);
    QByteArray bytes((char *)outputBuffer, cBuffer);
    emit bytesReceived(this, bytes);
}

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

366
    Q_ASSERT(request.target_system == _vehicleSystemId);
367

368 369 370 371
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

372
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
373 374
{
    mavlink_param_union_t   valueUnion;
375

376 377
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
378
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
379

380
    valueUnion.param_float = paramFloat;
381

382
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
383

384
    QVariant paramVariant;
385

386 387 388 389
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
390

391 392 393
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
394

395 396 397
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
398

399 400 401
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
402

403 404
        default:
            qCritical() << "Invalid parameter type" << paramType;
405
    }
406

407
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
408
    _mapParamName2Value[componentId][paramName] = paramVariant;
409 410
}

411
/// Convert from a parameter variant to the float value from mavlink_param_union_t
412
float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
413
{
414
    mavlink_param_union_t   valueUnion;
415

416 417
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramName));
418
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
419

420
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
421
    QVariant paramVar = _mapParamName2Value[componentId][paramName];
422

423 424 425 426
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            break;
427

428 429 430
        case MAV_PARAM_TYPE_INT32:
            valueUnion.param_int32 = paramVar.toInt();
            break;
431

432 433 434
        case MAV_PARAM_TYPE_UINT32:
            valueUnion.param_uint32 = paramVar.toUInt();
            break;
435

436 437 438
        case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
            break;
439

440 441 442
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
443

444
    return valueUnion.param_float;
445 446 447 448 449
}

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

451
    mavlink_msg_param_request_list_decode(&msg, &request);
452

453
    Q_ASSERT(request.target_system == _vehicleSystemId);
454 455 456
    Q_ASSERT(request.target_component == MAV_COMP_ID_ALL);

    foreach (int componentId, _mapParamName2Value.keys()) {
457
        uint16_t paramIndex = 1;
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
        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);

            qCDebug(MockLinkLog) << "Sending msg_param_value" << paramId << paramType;

            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
            _emitMavlinkMessage(responseMsg);
        }
484 485 486 487 488 489 490
    }
}

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

492
    Q_ASSERT(request.target_system == _vehicleSystemId);
493
    int componentId = request.target_component;
494 495 496 497

    // Param may not be null terminated if exactly fits
    char paramId[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
    strncpy(paramId, request.param_id, MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN);
498

499 500
    Q_ASSERT(_mapParamName2Value.contains(componentId));
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
501
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
502

503
    // Save the new value
504
    _setParamFloatUnionIntoMap(componentId, paramId, request.param_value);
505

506 507 508
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
509 510 511 512 513 514 515
                                 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
516
    _emitMavlinkMessage(responseMsg);
517 518 519 520 521 522
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
523 524 525
    
    int componentId = request.target_component;
    Q_ASSERT(_mapParamName2Value.contains(componentId));
526

527 528
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
529

530
    Q_ASSERT(request.target_system == _vehicleSystemId);
531

532 533 534
    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);
535
    } else {
536
        // Request is by index
537

538
        Q_ASSERT(request.param_index >= 0 && request.param_index < _mapParamName2Value.count());
539

540
        QString key = _mapParamName2Value[componentId].keys().at(request.param_index);
541 542
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
543
    }
544

545
    Q_ASSERT(_mapParamName2Value[componentId].contains(paramId));
546
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
547

548
    mavlink_message_t   responseMsg;
549

550
    mavlink_msg_param_value_pack(_vehicleSystemId,
551 552 553 554 555 556 557
                                 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
558
    _emitMavlinkMessage(responseMsg);
559 560 561 562 563
}

void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
{
    mavlink_mission_request_list_t request;
564

565
    mavlink_msg_mission_request_list_decode(&msg, &request);
566

567
    Q_ASSERT(request.target_system == _vehicleSystemId);
568

569 570 571 572 573 574 575 576 577
    mavlink_message_t   responseMsg;

    mavlink_msg_mission_count_pack(_vehicleSystemId,
                                   _vehicleComponentId,
                                   &responseMsg,            // Outgoing message
                                   msg.sysid,               // Target is original sender
                                   msg.compid,              // Target is original sender
                                   _missionItems.count());  // Number of mission items
    _emitMavlinkMessage(responseMsg);
578 579 580 581 582
}

void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
{
    mavlink_mission_request_t request;
583

584
    mavlink_msg_mission_request_decode(&msg, &request);
585

586 587
    Q_ASSERT(request.target_system == _vehicleSystemId);
    Q_ASSERT(request.seq < _missionItems.count());
588

589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605
    mavlink_message_t   responseMsg;

    mavlink_mission_item_t item = _missionItems[request.seq];

    mavlink_msg_mission_item_pack(_vehicleSystemId,
                                  _vehicleComponentId,
                                  &responseMsg,            // Outgoing message
                                  msg.sysid,               // Target is original sender
                                  msg.compid,              // Target is original sender
                                  request.seq,             // Index of mission item being sent
                                  item.frame,
                                  item.command,
                                  item.current,
                                  item.autocontinue,
                                  item.param1, item.param2, item.param3, item.param4,
                                  item.x, item.y, item.z);
    _emitMavlinkMessage(responseMsg);
606 607 608 609 610
}

void MockLink::_handleMissionItem(const mavlink_message_t& msg)
{
    mavlink_mission_item_t request;
611

612
    mavlink_msg_mission_item_decode(&msg, &request);
613

614
    Q_ASSERT(request.target_system == _vehicleSystemId);
615

616 617
    // FIXME: What do you do with duplication sequence numbers?
    Q_ASSERT(!_missionItems.contains(request.seq));
618

619
    _missionItems[request.seq] = request;
620
}