MAVLinkProtocol.cc 27.9 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5
======================================================================*/

/**
 * @file
pixhawk's avatar
pixhawk committed
6 7
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
8 9 10 11 12 13 14
 */

#include <inttypes.h>
#include <iostream>

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
15
#include <QApplication>
pixhawk's avatar
pixhawk committed
16
#include <QMessageBox>
17 18
#include <QSettings>
#include <QDesktopServices>
19
#include <QtEndian>
20
#include <QMetaType>
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26

#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
27 28
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
29
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
30 31
#include "configuration.h"
#include "LinkManager.h"
32 33
#include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
34
#include "QGC.h"
pixhawk's avatar
pixhawk committed
35

36 37 38 39
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif

40
Q_DECLARE_METATYPE(mavlink_message_t)
41

pixhawk's avatar
pixhawk committed
42 43 44 45 46
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
MAVLinkProtocol::MAVLinkProtocol() :
47
    heartbeatTimer(NULL),
48
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
49
    m_heartbeatsEnabled(true),
50 51 52 53 54 55 56 57 58 59 60
    m_multiplexingEnabled(false),
    m_authEnabled(false),
    m_loggingEnabled(false),
    m_logfile(NULL),
    m_enable_version_check(true),
    m_paramRetransmissionTimeout(350),
    m_paramRewriteTimeout(500),
    m_paramGuardEnabled(true),
    m_actionGuardEnabled(false),
    m_actionRetransmissionTimeout(100),
    versionMismatchIgnore(false),
61 62
    systemId(QGC::defaultSystemId),
    _should_exit(false)
pixhawk's avatar
pixhawk committed
63
{
64 65
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

66
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
67
    loadSettings();
Lorenz Meier's avatar
Lorenz Meier committed
68
    moveToThread(this);
69 70 71 72 73

    // All the *Counter variables are not initialized here, as they should be initialized
    // on a per-link basis before those links are used. @see resetMetadataForLink().

    // Initialize the list for tracking dropped messages to invalid.
74 75 76 77
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
78 79 80
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
81

Lorenz Meier's avatar
Lorenz Meier committed
82 83
    start(QThread::HighPriority);

lm's avatar
lm committed
84
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
85 86
}

87 88 89 90 91 92
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.sync();
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
93
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool());
94 95
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
96 97

    // Only set logfile if there is a name present in settings
98 99
    if (settings.contains("LOGFILE_NAME") && m_logfile == NULL)
    {
100
        m_logfile = new QFile(settings.value("LOGFILE_NAME").toString());
101 102 103
    }
    else if (m_logfile == NULL)
    {
104 105
        m_logfile = new QFile(QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink");
    }
106 107
    // Enable logging
    enableLogging(settings.value("LOGGING_ENABLED", m_loggingEnabled).toBool());
108 109 110

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
111 112
    if (temp > 0 && temp < 256)
    {
113 114
        systemId = temp;
    }
115

116 117 118 119
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

120 121 122 123 124 125 126
    // Parameter interface settings
    bool ok;
    temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout).toInt(&ok);
    if (ok) m_paramRetransmissionTimeout = temp;
    temp = settings.value("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout).toInt(&ok);
    if (ok) m_paramRewriteTimeout = temp;
    m_paramGuardEnabled = settings.value("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled).toBool();
127 128 129 130 131 132 133 134 135 136
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
    settings.setValue("HEARTBEATS_ENABLED", m_heartbeatsEnabled);
    settings.setValue("LOGGING_ENABLED", m_loggingEnabled);
137 138
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
139
    settings.setValue("GCS_SYSTEM_ID", systemId);
140 141
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
142 143
    if (m_logfile)
    {
144 145 146
        // Logfile exists, store the name
        settings.setValue("LOGFILE_NAME", m_logfile->fileName());
    }
147 148 149 150
    // Parameter interface settings
    settings.setValue("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout);
    settings.setValue("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout);
    settings.setValue("PARAMETER_TRANSMISSION_GUARD_ENABLED", m_paramGuardEnabled);
151 152 153 154 155
    settings.endGroup();
    settings.sync();
    //qDebug() << "Storing settings!";
}

pixhawk's avatar
pixhawk committed
156 157
MAVLinkProtocol::~MAVLinkProtocol()
{
158
    storeSettings();
159 160 161 162
    if (m_logfile)
    {
        if (m_logfile->isOpen())
        {
163 164 165
            m_logfile->flush();
            m_logfile->close();
        }
pixhawk's avatar
pixhawk committed
166
        delete m_logfile;
167
        m_logfile = NULL;
pixhawk's avatar
pixhawk committed
168
    }
Lorenz Meier's avatar
Lorenz Meier committed
169 170

    // Tell the thread to exit
171
    _should_exit = true;
Lorenz Meier's avatar
Lorenz Meier committed
172 173 174 175 176 177 178 179 180 181
    // Wait for it to exit
    wait();
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkProtocol::run()
{
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197
    heartbeatTimer = new QTimer();
    heartbeatTimer->moveToThread(this);
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);

    while(!_should_exit) {

        if (isFinished()) {
            qDebug() << "MAVLINK WORKER DONE!";
            return;
        }

        QCoreApplication::processEvents();
        QGC::SLEEP::msleep(2);
    }
pixhawk's avatar
pixhawk committed
198 199
}

pixhawk's avatar
pixhawk committed
200 201
QString MAVLinkProtocol::getLogfileName()
{
202 203
    if (m_logfile)
    {
204
        return m_logfile->fileName();
205 206 207
    }
    else
    {
208
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
209
    }
pixhawk's avatar
pixhawk committed
210 211
}

212 213 214 215 216 217 218 219 220 221
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
    int linkId = link->getId();
    totalReceiveCounter[linkId] = 0;
    totalLossCounter[linkId] = 0;
    totalErrorCounter[linkId] = 0;
    currReceiveCounter[linkId] = 0;
    currLossCounter[linkId] = 0;
}

222 223 224 225 226 227 228 229 230 231
void MAVLinkProtocol::linkStatusChanged(bool connected)
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());

    if (link) {
        if (connected) {
            // Send command to start MAVLink
            // XXX hacky but safe
            // Start NSH
            const char init[] = {0x0d, 0x0d, 0x0d};
Lorenz Meier's avatar
Lorenz Meier committed
232
            link->writeBytes(init, sizeof(init));
233
            const char* cmd = "sh /etc/init.d/rc.usb\n";
234 235 236 237 238 239
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 4);
        }
    }
}

pixhawk's avatar
pixhawk committed
240 241 242 243 244 245 246
/**
 * This method parses all incoming bytes and constructs a MAVLink packet.
 * It can handle multiple links in parallel, as each link has it's own buffer/
 * parsing state machine.
 * @param link The interface to read from
 * @see LinkInterface
 **/
247
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
248
{
249
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
250 251
    mavlink_message_t message;
    mavlink_status_t status;
252

253 254 255
    // Cache the link ID for common use.
    int linkId = link->getId();

256
    static int mavlink09Count = 0;
257
    static int nonmavlinkCount = 0;
258
    static bool decodedFirstPacket = false;
259
    static bool warnedUser = false;
260 261
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
262

263
    // FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
264
    for (int position = 0; position < b.size(); position++) {
265
        unsigned int decodeState = mavlink_parse_char(linkId, (uint8_t)(b[position]), &message, &status);
266 267

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
268
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
269
        {
270
            warnedUser = true;
271 272
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
273
            emit protocolStatusMessage("MAVLink Version or Baud Rate Mismatch", "Your MAVLink device seems to use the deprecated version 0.9, while QGroundControl only supports version 1.0+. Please upgrade the MAVLink version of your autopilot. If your autopilot is using version 1.0, check if the baud rates of QGroundControl and your autopilot are the same.");
274
        }
pixhawk's avatar
pixhawk committed
275

276 277 278
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
279
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
280
            {
281
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
282 283 284 285 286 287 288 289 290 291 292 293
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
                    emit protocolStatusMessage("MAVLink Baud Rate Mismatch", "Please check if the baud rates of QGroundControl and your autopilot are the same.");
                }
            }
        }
294 295
        if (decodeState == 1)
        {
296
            decodedFirstPacket = true;
297 298 299 300 301 302 303 304 305 306 307 308 309 310

            if(message.msgid == MAVLINK_MSG_ID_PING)
            {
                // process ping requests (tgt_system and tgt_comp must be zero)
                mavlink_ping_t ping;
                mavlink_msg_ping_decode(&message, &ping);
                if(!ping.target_system && !ping.target_component)
                {
                    mavlink_message_t msg;
                    mavlink_msg_ping_pack(getSystemId(), getComponentId(), &msg, ping.time_usec, ping.seq, message.sysid, message.compid);
                    sendMessage(msg);
                }
            }

311
#if defined(QGC_PROTOBUF_ENABLED)
LM's avatar
LM committed
312

313 314
            if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
            {
315 316 317 318 319 320
                mavlink_extended_message_t extended_message;

                extended_message.base_msg = message;

                // read extended header
                uint8_t* payload = reinterpret_cast<uint8_t*>(message.payload64);
LM's avatar
LM committed
321

322 323
                memcpy(&extended_message.extended_payload_len, payload + 3, 4);

LM's avatar
LM committed
324 325 326 327 328 329 330 331 332
                // Check if message is valid
                if
                 (b.size() != MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_EXTENDED_HEADER_LEN+ extended_message.extended_payload_len)
                {
                    //invalid message
                    qDebug() << "GOT INVALID EXTENDED MESSAGE, ABORTING";
                    return;
                }

333 334 335 336 337
                const uint8_t* extended_payload = reinterpret_cast<const uint8_t*>(b.constData()) + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_EXTENDED_HEADER_LEN;

                // copy extended payload data
                memcpy(extended_message.extended_payload, extended_payload, extended_message.extended_payload_len);

338 339
#if defined(QGC_USE_PIXHAWK_MESSAGES)

340 341 342 343 344 345
                if (protobufManager.cacheFragment(extended_message))
                {
                    std::tr1::shared_ptr<google::protobuf::Message> protobuf_msg;

                    if (protobufManager.getMessage(protobuf_msg))
                    {
346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381
                        const google::protobuf::Descriptor* descriptor = protobuf_msg->GetDescriptor();
                        if (!descriptor)
                        {
                            continue;
                        }

                        const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
                        if (!headerField)
                        {
                            continue;
                        }

                        const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
                        if (!headerDescriptor)
                        {
                            continue;
                        }

                        const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
                        if (!sourceSysIdField)
                        {
                            continue;
                        }

                        const google::protobuf::Reflection* reflection = protobuf_msg->GetReflection();
                        const google::protobuf::Message& headerMsg = reflection->GetMessage(*protobuf_msg, headerField);
                        const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();

                        int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);

                        UASInterface* uas = UASManager::instance()->getUASForId(source_sysid);

                        if (uas != NULL)
                        {
                            emit extendedMessageReceived(link, protobuf_msg);
                        }
382 383
                    }
                }
384
#endif
385 386 387 388

                position += extended_message.extended_payload_len;

                continue;
389 390 391
            }
#endif

pixhawk's avatar
pixhawk committed
392
            // Log data
393 394
            if (m_loggingEnabled && m_logfile)
            {
395 396 397 398 399 400 401 402 403 404 405 406 407 408 409
                uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)];

                // Write the uint64 time in microseconds in big endian format before the message.
                // This timestamp is saved in UTC time. We are only saving in ms precision because
                // getting more than this isn't possible with Qt without a ton of extra code.
                quint64 time = (quint64)QDateTime::currentMSecsSinceEpoch() * 1000;
                qToBigEndian(time, buf);

                // Then write the message to the buffer
                int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &message);

                // Determine how many bytes were written by adding the timestamp size to the message size
                len += sizeof(quint64);

                // Now write this timestamp/message pair to the log.
410
                QByteArray b((const char*)buf, len);
Lorenz Meier's avatar
Lorenz Meier committed
411
                if(m_logfile->write(b) != len)
412
                {
413
                    // If there's an error logging data, raise an alert and stop logging.
414 415 416
                    emit protocolStatusMessage(tr("MAVLink Logging failed"), tr("Could not write to file %1, disabling logging.").arg(m_logfile->fileName()));
                    enableLogging(false);
                }
pixhawk's avatar
pixhawk committed
417 418
            }

pixhawk's avatar
pixhawk committed
419 420 421
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
422

pixhawk's avatar
pixhawk committed
423 424 425
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
426 427
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
428 429 430 431 432 433
                // ORDER MATTERS HERE!
                // The UAS object has first to be created and connected,
                // only then the rest of the application can be made aware
                // of its existence, as it only then can send and receive
                // it's first messages.

pixhawk's avatar
pixhawk committed
434
                // Check if the UAS has the same id like this system
435 436
                if (message.sysid == getSystemId())
                {
437
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
438 439
                }

440 441 442 443
                // Create a new UAS based on the heartbeat received
                // Todo dynamically load plugin at run-time for MAV
                // WIKISEARCH:AUTOPILOT_TYPE_INSTANTIATION

pixhawk's avatar
pixhawk committed
444
                // First create new UAS object
445 446
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
447 448
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
449
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
450 451

                // Check if the UAS has a different protocol version
452 453
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
454
                    // Bring up dialog to inform user
455 456
                    if (!versionMismatchIgnore)
                    {
457
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
458
                                                   tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
459 460
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
461 462 463 464 465

                    // Ignore this message and continue gracefully
                    continue;
                }

466 467
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
468

pixhawk's avatar
pixhawk committed
469
            }
470 471

            // Only count message if UAS exists for this message
472 473
            if (uas != NULL)
            {
474

475
                // Increase receive counter
476 477
                totalReceiveCounter[linkId]++;
                currReceiveCounter[linkId]++;
478 479 480

                // Update last message sequence ID
                uint8_t expectedIndex;
481
                if (lastIndex[message.sysid][message.compid] == -1)
482
                {
483
                    lastIndex[message.sysid][message.compid] = message.seq;
484
                    expectedIndex = message.seq;
485
                }
486 487
                else
                {
488
                    // NOTE: Using uint8_t here auto-wraps the number around to 0.
489
                    expectedIndex = lastIndex[message.sysid][message.compid] + 1;
490 491 492
                }

                // Make some noise if a message was skipped
493
                //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "EXPECTED INDEX:" << expectedIndex << "SEQ" << message.seq;
494 495 496
                if (message.seq != expectedIndex)
                {
                    // Determine how many messages were skipped accounting for 0-wraparound
497
                    int16_t lostMessages = message.seq - expectedIndex;
498 499 500 501 502 503 504
                    if (lostMessages < 0)
                    {
                        // Usually, this happens in the case of an out-of order packet
                        lostMessages = 0;
                    }
                    else
                    {
LM's avatar
LM committed
505 506
                        // Console generates excessive load at high loss rates, needs better GUI visualization
                        //qDebug() << QString("Lost %1 messages for comp %4: expected sequence ID %2 but received %3.").arg(lostMessages).arg(expectedIndex).arg(message.seq).arg(message.compid);
507
                    }
508 509
                    totalLossCounter[linkId] += lostMessages;
                    currLossCounter[linkId] += lostMessages;
510
                }
511 512 513

                // Update the last sequence ID
                lastIndex[message.sysid][message.compid] = message.seq;
514

515
                // Update on every 32th packet
516
                if (totalReceiveCounter[linkId] % 32 == 0)
517
                {
518 519
                    // Calculate new loss ratio
                    // Receive loss
520
                    float receiveLoss = (double)currLossCounter[linkId]/(double)(currReceiveCounter[linkId]+currLossCounter[linkId]);
521
                    receiveLoss *= 100.0f;
522 523
                    currLossCounter[linkId] = 0;
                    currReceiveCounter[linkId] = 0;
pixhawk's avatar
pixhawk committed
524
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
525 526
                }

527 528 529 530
                // The packet is emitted as a whole, as it is only 255 - 261 bytes short
                // kind of inefficient, but no issue for a groundstation pc.
                // It buys as reentrancy for the whole code over all threads
                emit messageReceived(link, message);
531 532

                // Multiplex message if enabled
533 534
                if (m_multiplexingEnabled)
                {
535 536 537 538
                    // Get all links connected to this unit
                    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

                    // Emit message on all links that are currently connected
539 540
                    foreach (LinkInterface* currLink, links)
                    {
541 542
                        // Only forward this message to the other links,
                        // not the link the message was received on
Lorenz Meier's avatar
Lorenz Meier committed
543
                        if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
544 545
                    }
                }
546
            }
pixhawk's avatar
pixhawk committed
547 548 549 550 551 552 553 554 555 556 557 558
        }
    }
}

/**
 * @return The name of this protocol
 **/
QString MAVLinkProtocol::getName()
{
    return QString(tr("MAVLink protocol"));
}

559
/** @return System id of this application */
560
int MAVLinkProtocol::getSystemId()
561
{
562 563 564 565 566 567
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
568 569 570
}

/** @return Component id of this application */
571
int MAVLinkProtocol::getComponentId()
572
{
573
    return QGC::defaultComponentId;
574 575
}

pixhawk's avatar
pixhawk committed
576 577 578 579 580 581 582 583 584 585
/**
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
{
    // Get all links connected to this unit
    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
586 587
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
588
        sendMessage(*i, message);
589
//        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
590 591 592 593 594 595 596 597 598 599
    }
}

/**
 * @param link the link to send the message over
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
{
    // Create buffer
Lorenz Meier's avatar
Lorenz Meier committed
600
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
601
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
602 603
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
604
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
605
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
606
    // If link is connected
607 608
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
609 610 611 612 613
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636
/**
 * @param link the link to send the message over
 * @param message message to send
 * @param systemid id of the system the message is originating from
 * @param componentid id of the component the message is originating from
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
{
    // Create buffer
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Rewriting header to ensure correct link ID is set
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, systemid, componentid, link->getId(), message.len, messageKeys[message.msgid]);
    // Write message into buffer, prepending start sign
    int len = mavlink_msg_to_send_buffer(buffer, &message);
    // If link is connected
    if (link->isConnected())
    {
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

pixhawk's avatar
pixhawk committed
637 638 639 640 641 642 643
/**
 * The heartbeat is sent out of order and does not reset the
 * periodic heartbeat emission. It will be just sent in addition.
 * @return mavlink_message_t heartbeat message sent on serial link
 */
void MAVLinkProtocol::sendHeartbeat()
{
Lorenz Meier's avatar
Lorenz Meier committed
644 645
    if (m_heartbeatsEnabled)
    {
pixhawk's avatar
pixhawk committed
646
        mavlink_message_t beat;
lm's avatar
lm committed
647
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
pixhawk's avatar
pixhawk committed
648 649
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
650 651
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
652 653
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
654
        memset(&auth, 0, sizeof(auth));
655
        memcpy(auth.key, m_authKey.toStdString().c_str(), qMin(m_authKey.length(), MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN));
James Goppert's avatar
James Goppert committed
656 657 658
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
659 660 661 662 663 664 665 666 667
}

/** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
    m_heartbeatsEnabled = enabled;
    emit heartbeatChanged(enabled);
}

668 669 670 671 672 673 674 675 676
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

    m_multiplexingEnabled = enabled;
    if (changed) emit multiplexingChanged(m_multiplexingEnabled);
}

677 678 679 680
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
681
    if (m_authEnabled != enable) {
682 683 684 685 686
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

687 688
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
689
    if (enabled != m_paramGuardEnabled) {
690 691 692 693 694
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

695 696
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
697
    if (enabled != m_actionGuardEnabled) {
698 699 700 701 702
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

703 704
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
705
    if (ms != m_paramRetransmissionTimeout) {
706 707 708 709 710 711 712
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
713
    if (ms != m_paramRewriteTimeout) {
714 715 716 717 718
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

719 720
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
721
    if (ms != m_actionRetransmissionTimeout) {
722 723 724 725 726
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
727 728
void MAVLinkProtocol::enableLogging(bool enabled)
{
729 730 731
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

732 733 734 735
    if (enabled)
    {
        if (m_logfile && m_logfile->isOpen())
        {
736 737 738
            m_logfile->flush();
            m_logfile->close();
        }
739 740 741 742 743

        if (m_logfile)
        {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
            {
744 745
                emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot log to the file %1, please choose a different file. Stopping logging.").arg(m_logfile->fileName()));
                m_loggingEnabled = false;
746
            }
747
        }
748 749 750 751 752 753 754 755 756 757 758
        else
        {
            emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot start logging, no logfile selected."));
        }
    }
    else if (!enabled)
    {
        if (m_logfile)
        {
            if (m_logfile->isOpen())
            {
759 760 761
                m_logfile->flush();
                m_logfile->close();
            }
762
        }
lm's avatar
lm committed
763 764
    }
    m_loggingEnabled = enabled;
765
    if (changed) emit loggingChanged(enabled);
766 767 768 769
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
770 771
    if (!m_logfile)
    {
772
        m_logfile = new QFile(filename);
773 774 775
    }
    else
    {
776 777 778
        m_logfile->flush();
        m_logfile->close();
    }
779
    m_logfile->setFileName(filename);
780
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
781 782
}

lm's avatar
lm committed
783 784 785
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
786
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
787 788
}

pixhawk's avatar
pixhawk committed
789 790 791 792 793 794 795 796
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
    heartbeatRate = rate;
797
    heartbeatTimer->setInterval(1000/heartbeatRate);
pixhawk's avatar
pixhawk committed
798 799 800 801 802 803 804
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
    return heartbeatRate;
}