MockLink.cc 19.5 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 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.
 
 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.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

#include "MockLink.h"

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

#include <string.h>

32 33
Q_LOGGING_CATEGORY(MockLinkLog, "MockLinkLog")

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

Don Gagne's avatar
Don Gagne committed
39 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
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;
};

68 69 70 71 72 73 74 75
MockLink::MockLink(void) :
    _linkId(getNextLinkId()),
    _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
{
Don Gagne's avatar
Don Gagne committed
80 81 82 83 84 85
    union px4_custom_mode   px4_cm;

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

86 87 88 89 90 91 92 93 94 95
    _missionItemHandler = new MockLinkMissionItemHandler(_vehicleSystemId, this);
    Q_CHECK_PTR(_missionItemHandler);
    
    moveToThread(this);
    _loadParams();
    QObject::connect(this, &MockLink::_incomingBytes, this, &MockLink::_handleIncomingBytes);
}

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

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

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

115
bool MockLink::_disconnect(void)
116
{
117 118 119 120 121
    if (_connected) {
        _connected = false;
        exit();        
        emit disconnected();
    }
122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140
    
    return true;
}

void MockLink::run(void)
{
    QTimer  _timer1HzTasks;
    QTimer  _timer10HzTasks;
    QTimer  _timer50HzTasks;
    
    QObject::connect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::connect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::connect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
    
    _timer1HzTasks.start(1000);
    _timer10HzTasks.start(100);
    _timer50HzTasks.start(20);
    
    exec();
141 142 143 144
    
    QObject::disconnect(&_timer1HzTasks, &QTimer::timeout, this, &MockLink::_run1HzTasks);
    QObject::disconnect(&_timer10HzTasks, &QTimer::timeout, this, &MockLink::_run10HzTasks);
    QObject::disconnect(&_timer50HzTasks, &QTimer::timeout, this, &MockLink::_run50HzTasks);
145 146 147 148
}

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

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

void MockLink::_run50HzTasks(void)
{
162
    if (_mavlinkStarted && _connected) {
163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208
    }
}

void MockLink::_loadParams(void)
{
    QFile paramFile(":/unittest/MockLink.param");
    
    bool success = paramFile.open(QFile::ReadOnly);
    Q_UNUSED(success);
    Q_ASSERT(success);
    
    QTextStream paramStream(&paramFile);
    
    while (!paramStream.atEnd()) {
        QString line = paramStream.readLine();
        
        if (line.startsWith("#")) {
            continue;
        }
        
        QStringList paramData = line.split("\t");
        Q_ASSERT(paramData.count() == 5);
        
        QString paramName = paramData.at(2);
        QString valStr = paramData.at(3);
        uint paramType = paramData.at(4).toUInt();
        
        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;
        }
        
209 210
        _mapParamName2Value[paramName] = paramValue;
        _mapParamName2MavParamType[paramName] = static_cast<MAV_PARAM_TYPE>(paramType);
211 212 213 214 215 216 217 218 219 220 221 222
    }
}

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
223
                               _autopilotType,      // MAV_AUTOPILOT
Don Gagne's avatar
Don Gagne committed
224 225
                               _mavBaseMode,        // MAV_MODE
                               _mavCustomMode,      // custom mode
226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361
                               _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);
    
    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);
        }
        
        _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);
    
    // 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;
        
        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;
    
    for (qint64 i=0; i<cBytes; i++)
    {
        if (!mavlink_parse_char(_linkId, bytes[i], &msg, &comm)) {
            continue;
        }
        
        Q_ASSERT(_missionItemHandler);
        _missionItemHandler->handleMessage(msg);
        
        switch (msg.msgid) {
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartBeat(msg);
                break;
                
            case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
                _handleParamRequestList(msg);
                break;
                
            case MAVLINK_MSG_ID_SET_MODE:
                _handleSetMode(msg);
                break;
                
            case MAVLINK_MSG_ID_PARAM_SET:
                _handleParamSet(msg);
                break;
                
            case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
                _handleParamRequestRead(msg);
                break;
                
            case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
                _handleMissionRequestList(msg);
                break;
                
            case MAVLINK_MSG_ID_MISSION_REQUEST:
                _handleMissionRequest(msg);
                break;
                
            case MAVLINK_MSG_ID_MISSION_ITEM:
                _handleMissionItem(msg);
                break;
                
#if 0
            case MAVLINK_MSG_ID_MISSION_COUNT:
                _handleMissionCount(msg);
                break;
#endif
                
            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];
    
    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);
    
362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399
    Q_ASSERT(request.target_system == _vehicleSystemId);
    
    _mavBaseMode = request.base_mode;
    _mavCustomMode = request.custom_mode;
}

void MockLink::_setParamFloatUnionIntoMap(const QString& paramName, float paramFloat)
{
    mavlink_param_union_t   valueUnion;
    
    Q_ASSERT(_mapParamName2Value.contains(paramName));
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
    
    valueUnion.param_float = paramFloat;
    
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
    
    QVariant paramVariant;
    
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            paramVariant = QVariant::fromValue(valueUnion.param_int8);
            break;
            
        case MAV_PARAM_TYPE_INT32:
            paramVariant = QVariant::fromValue(valueUnion.param_int32);
            break;
            
        case MAV_PARAM_TYPE_UINT32:
            paramVariant = QVariant::fromValue(valueUnion.param_uint32);
            break;
            
        case MAV_PARAM_TYPE_REAL32:
            paramVariant = QVariant::fromValue(valueUnion.param_float);
            break;
            
        default:
            qCritical() << "Invalid parameter type" << paramType;
400
    }
401 402 403
    
    qCDebug(MockLinkLog) << "_setParamFloatUnionIntoMap" << paramName << paramVariant;
    _mapParamName2Value[paramName] = paramVariant;
404 405
}

406 407
/// Convert from a parameter variant to the float value from mavlink_param_union_t
float MockLink::_floatUnionForParam(const QString& paramName)
408
{
409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438
    mavlink_param_union_t   valueUnion;
    
    Q_ASSERT(_mapParamName2Value.contains(paramName));
    Q_ASSERT(_mapParamName2MavParamType.contains(paramName));
    
    MAV_PARAM_TYPE paramType = _mapParamName2MavParamType[paramName];
    QVariant paramVar = _mapParamName2Value[paramName];
    
    switch (paramType) {
        case MAV_PARAM_TYPE_INT8:
            valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
            break;
            
        case MAV_PARAM_TYPE_INT32:
            valueUnion.param_int32 = paramVar.toInt();
            break;
            
        case MAV_PARAM_TYPE_UINT32:
            valueUnion.param_uint32 = paramVar.toUInt();
            break;
            
        case MAV_PARAM_TYPE_REAL32:
            valueUnion.param_float = paramVar.toFloat();
            break;
            
        default:
            qCritical() << "Invalid parameter type" << paramType;
    }
    
    return valueUnion.param_float;
439 440 441 442
}

void MockLink::_handleParamRequestList(const mavlink_message_t& msg)
{
443
    uint16_t paramIndex = 0;
444 445 446 447
    mavlink_param_request_list_t request;
    
    mavlink_msg_param_request_list_decode(&msg, &request);
    
448 449 450 451 452 453 454
    int cParameters = _mapParamName2Value.count();
    
    Q_ASSERT(request.target_system == _vehicleSystemId);
    
    foreach(QString paramName, _mapParamName2Value.keys()) {
        char paramId[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
        mavlink_message_t       responseMsg;
455
        
456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472
        Q_ASSERT(_mapParamName2Value.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);
        
        mavlink_msg_param_value_pack(_vehicleSystemId,
                                     _vehicleComponentId,
                                     &responseMsg,                      // Outgoing message
                                     paramId,                           // Parameter name
                                     _floatUnionForParam(paramName),    // Parameter value
                                     paramType,                         // MAV_PARAM_TYPE
                                     cParameters,                       // Total number of parameters
                                     paramIndex++);                     // Index of this parameter
        _emitMavlinkMessage(responseMsg);
473 474 475 476 477 478 479 480
    }
}

void MockLink::_handleParamSet(const mavlink_message_t& msg)
{
    mavlink_param_set_t request;
    mavlink_msg_param_set_decode(&msg, &request);
    
481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503
    Q_ASSERT(request.target_system == _vehicleSystemId);

    // 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);
    
    Q_ASSERT(_mapParamName2Value.contains(paramId));
    Q_ASSERT(request.param_type == _mapParamName2MavParamType[paramId]);
    
    // Save the new value
    _setParamFloatUnionIntoMap(paramId, request.param_value);
    
    // Respond with a param_value to ack
    mavlink_message_t responseMsg;
    mavlink_msg_param_value_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &responseMsg,                  // Outgoing message
                                 paramId,                       // Parameter name
                                 request.param_value,           // Send same value back
                                 request.param_type,            // Send same type back
                                 _mapParamName2Value.count(),   // Total number of parameters
                                 _mapParamName2Value.keys().indexOf(paramId));  // Index of this parameter
    _emitMavlinkMessage(responseMsg);
504 505 506 507 508 509 510 511 512 513
}

void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
{
    mavlink_param_request_read_t request;
    mavlink_msg_param_request_read_decode(&msg, &request);
    
    char paramId[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN + 1];
    paramId[0] = 0;
    
514 515 516 517 518
    Q_ASSERT(request.target_system == _vehicleSystemId);
    
    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);
519
    } else {
520 521 522 523 524 525 526
        // Request is by index
        
        Q_ASSERT(request.param_index >= 0 && request.param_index < _mapParamName2Value.count());
        
        QString key = _mapParamName2Value.keys().at(request.param_index);
        Q_ASSERT(key.length() <= MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN);
        strcpy(paramId, key.toLocal8Bit().constData());
527
    }
528 529 530 531 532 533 534 535 536 537 538 539 540 541 542

    Q_ASSERT(_mapParamName2Value.contains(paramId));
    Q_ASSERT(_mapParamName2MavParamType.contains(paramId));
    
    mavlink_message_t   responseMsg;
    
    mavlink_msg_param_value_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &responseMsg,                          // Outgoing message
                                 paramId,                               // Parameter name
                                 _floatUnionForParam(paramId),          // Parameter value
                                 _mapParamName2MavParamType[paramId],   // Parameter type
                                 _mapParamName2Value.count(),           // Total number of parameters
                                 _mapParamName2Value.keys().indexOf(paramId));  // Index of this parameter
    _emitMavlinkMessage(responseMsg);
543 544 545 546 547 548 549 550
}

void MockLink::_handleMissionRequestList(const mavlink_message_t& msg)
{
    mavlink_mission_request_list_t request;
    
    mavlink_msg_mission_request_list_decode(&msg, &request);
    
551 552 553 554 555 556 557 558 559 560 561
    Q_ASSERT(request.target_system == _vehicleSystemId);
    
    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);
562 563 564 565 566 567 568 569
}

void MockLink::_handleMissionRequest(const mavlink_message_t& msg)
{
    mavlink_mission_request_t request;
    
    mavlink_msg_mission_request_decode(&msg, &request);
    
570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589
    Q_ASSERT(request.target_system == _vehicleSystemId);
    Q_ASSERT(request.seq < _missionItems.count());
    
    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);
590 591 592 593 594 595 596 597
}

void MockLink::_handleMissionItem(const mavlink_message_t& msg)
{
    mavlink_mission_item_t request;
    
    mavlink_msg_mission_item_decode(&msg, &request);
    
598 599 600 601 602 603
    Q_ASSERT(request.target_system == _vehicleSystemId);
    
    // FIXME: What do you do with duplication sequence numbers?
    Q_ASSERT(!_missionItems.contains(request.seq));
    
    _missionItems[request.seq] = request;
604
}