MAVLinkProtocol.cc 27.6 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 48
    heartbeatTimer(new QTimer(this)),
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
49
    m_heartbeatsEnabled(true),
50 51 52 53 54 55 56 57 58 59 60 61
    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),
    systemId(QGC::defaultSystemId)
pixhawk's avatar
pixhawk committed
62
{
63 64
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

65
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
66
    loadSettings();
Lorenz Meier's avatar
Lorenz Meier committed
67
    moveToThread(this);
pixhawk's avatar
pixhawk committed
68 69 70
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);
71 72 73 74 75

    // 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.
76 77 78 79
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
80 81 82
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
83

Lorenz Meier's avatar
Lorenz Meier committed
84 85
    start(QThread::HighPriority);

lm's avatar
lm committed
86
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
87 88
}

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

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

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

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

122 123 124 125 126 127 128
    // 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();
129 130 131 132 133 134 135 136 137 138
    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);
139 140
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
141
    settings.setValue("GCS_SYSTEM_ID", systemId);
142 143
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
144 145
    if (m_logfile)
    {
146 147 148
        // Logfile exists, store the name
        settings.setValue("LOGFILE_NAME", m_logfile->fileName());
    }
149 150 151 152
    // 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);
153 154 155 156 157
    settings.endGroup();
    settings.sync();
    //qDebug() << "Storing settings!";
}

pixhawk's avatar
pixhawk committed
158 159
MAVLinkProtocol::~MAVLinkProtocol()
{
160
    storeSettings();
161 162 163 164
    if (m_logfile)
    {
        if (m_logfile->isOpen())
        {
165 166 167
            m_logfile->flush();
            m_logfile->close();
        }
pixhawk's avatar
pixhawk committed
168
        delete m_logfile;
169
        m_logfile = NULL;
pixhawk's avatar
pixhawk committed
170
    }
Lorenz Meier's avatar
Lorenz Meier committed
171 172 173 174 175 176 177 178 179 180 181 182 183 184

    // Tell the thread to exit
    quit();
    // Wait for it to exit
    wait();
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkProtocol::run()
{
    exec();
pixhawk's avatar
pixhawk committed
185 186
}

pixhawk's avatar
pixhawk committed
187 188
QString MAVLinkProtocol::getLogfileName()
{
189 190
    if (m_logfile)
    {
191
        return m_logfile->fileName();
192 193 194
    }
    else
    {
195
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
196
    }
pixhawk's avatar
pixhawk committed
197 198
}

199 200 201 202 203 204 205 206 207 208
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;
}

209 210 211 212 213 214 215 216 217 218
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
219
            link->writeBytes(init, sizeof(init));
220
            const char* cmd = "sh /etc/init.d/rc.usb\n";
221 222 223 224 225 226
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 4);
        }
    }
}

pixhawk's avatar
pixhawk committed
227 228 229 230 231 232 233
/**
 * 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
 **/
234
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
235
{
236
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
237 238
    mavlink_message_t message;
    mavlink_status_t status;
239

240 241 242
    // Cache the link ID for common use.
    int linkId = link->getId();

243
    static int mavlink09Count = 0;
244
    static int nonmavlinkCount = 0;
245
    static bool decodedFirstPacket = false;
246
    static bool warnedUser = false;
247 248
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
249

250
    // FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
251
    for (int position = 0; position < b.size(); position++) {
252
        unsigned int decodeState = mavlink_parse_char(linkId, (uint8_t)(b[position]), &message, &status);
253 254

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
255
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
256
        {
257
            warnedUser = true;
258 259
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
260
            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.");
261
        }
pixhawk's avatar
pixhawk committed
262

263 264 265
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
266
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
267
            {
268
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
269 270 271 272 273 274 275 276 277 278 279 280
                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.");
                }
            }
        }
281 282
        if (decodeState == 1)
        {
283
            decodedFirstPacket = true;
284 285 286 287 288 289 290 291 292 293 294 295 296 297

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

298
#if defined(QGC_PROTOBUF_ENABLED)
LM's avatar
LM committed
299

300 301
            if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
            {
302 303 304 305 306 307
                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
308

309 310
                memcpy(&extended_message.extended_payload_len, payload + 3, 4);

LM's avatar
LM committed
311 312 313 314 315 316 317 318 319
                // 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;
                }

320 321 322 323 324
                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);

325 326
#if defined(QGC_USE_PIXHAWK_MESSAGES)

327 328 329 330 331 332
                if (protobufManager.cacheFragment(extended_message))
                {
                    std::tr1::shared_ptr<google::protobuf::Message> protobuf_msg;

                    if (protobufManager.getMessage(protobuf_msg))
                    {
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 362 363 364 365 366 367 368
                        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);
                        }
369 370
                    }
                }
371
#endif
372 373 374 375

                position += extended_message.extended_payload_len;

                continue;
376 377 378
            }
#endif

pixhawk's avatar
pixhawk committed
379
            // Log data
380 381
            if (m_loggingEnabled && m_logfile)
            {
382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
                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.
397
                QByteArray b((const char*)buf, len);
Lorenz Meier's avatar
Lorenz Meier committed
398
                if(m_logfile->write(b) != len)
399
                {
400
                    // If there's an error logging data, raise an alert and stop logging.
401 402 403
                    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
404 405
            }

pixhawk's avatar
pixhawk committed
406 407 408
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
409

pixhawk's avatar
pixhawk committed
410 411 412
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
413 414
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
415 416 417 418 419 420
                // 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
421
                // Check if the UAS has the same id like this system
422 423
                if (message.sysid == getSystemId())
                {
424
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
425 426
                }

427 428 429 430
                // 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
431
                // First create new UAS object
432 433
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
434 435
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
436
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
437 438

                // Check if the UAS has a different protocol version
439 440
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
441
                    // Bring up dialog to inform user
442 443
                    if (!versionMismatchIgnore)
                    {
444
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
445
                                                   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));
446 447
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
448 449 450 451 452

                    // Ignore this message and continue gracefully
                    continue;
                }

453 454
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
455

pixhawk's avatar
pixhawk committed
456
            }
457 458

            // Only count message if UAS exists for this message
459 460
            if (uas != NULL)
            {
461

462
                // Increase receive counter
463 464
                totalReceiveCounter[linkId]++;
                currReceiveCounter[linkId]++;
465 466 467

                // Update last message sequence ID
                uint8_t expectedIndex;
468
                if (lastIndex[message.sysid][message.compid] == -1)
469
                {
470
                    lastIndex[message.sysid][message.compid] = message.seq;
471
                    expectedIndex = message.seq;
472
                }
473 474
                else
                {
475
                    // NOTE: Using uint8_t here auto-wraps the number around to 0.
476
                    expectedIndex = lastIndex[message.sysid][message.compid] + 1;
477 478 479
                }

                // Make some noise if a message was skipped
480
                //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "EXPECTED INDEX:" << expectedIndex << "SEQ" << message.seq;
481 482 483
                if (message.seq != expectedIndex)
                {
                    // Determine how many messages were skipped accounting for 0-wraparound
484
                    int16_t lostMessages = message.seq - expectedIndex;
485 486 487 488 489 490 491
                    if (lostMessages < 0)
                    {
                        // Usually, this happens in the case of an out-of order packet
                        lostMessages = 0;
                    }
                    else
                    {
LM's avatar
LM committed
492 493
                        // 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);
494
                    }
495 496
                    totalLossCounter[linkId] += lostMessages;
                    currLossCounter[linkId] += lostMessages;
497
                }
498 499 500

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

502
                // Update on every 32th packet
503
                if (totalReceiveCounter[linkId] % 32 == 0)
504
                {
505 506
                    // Calculate new loss ratio
                    // Receive loss
507
                    float receiveLoss = (double)currLossCounter[linkId]/(double)(currReceiveCounter[linkId]+currLossCounter[linkId]);
508
                    receiveLoss *= 100.0f;
509 510
                    currLossCounter[linkId] = 0;
                    currReceiveCounter[linkId] = 0;
pixhawk's avatar
pixhawk committed
511
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
512 513
                }

514 515 516 517
                // 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);
518 519

                // Multiplex message if enabled
520 521
                if (m_multiplexingEnabled)
                {
522 523 524 525
                    // Get all links connected to this unit
                    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

                    // Emit message on all links that are currently connected
526 527
                    foreach (LinkInterface* currLink, links)
                    {
528 529
                        // Only forward this message to the other links,
                        // not the link the message was received on
Lorenz Meier's avatar
Lorenz Meier committed
530
                        if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
531 532
                    }
                }
533
            }
pixhawk's avatar
pixhawk committed
534 535 536 537 538 539 540 541 542 543 544 545
        }
    }
}

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

546
/** @return System id of this application */
547
int MAVLinkProtocol::getSystemId()
548
{
549 550 551 552 553 554
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
555 556 557
}

/** @return Component id of this application */
558
int MAVLinkProtocol::getComponentId()
559
{
560
    return QGC::defaultComponentId;
561 562
}

pixhawk's avatar
pixhawk committed
563 564 565 566 567 568 569 570 571 572
/**
 * @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;
573 574
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
575
        sendMessage(*i, message);
576
//        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
577 578 579 580 581 582 583 584 585 586
    }
}

/**
 * @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
587
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
588
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
589 590
    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
591
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
592
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
593
    // If link is connected
594 595
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
596 597 598 599 600
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623
/**
 * @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
624 625 626 627 628 629 630
/**
 * 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
631 632
    if (m_heartbeatsEnabled)
    {
pixhawk's avatar
pixhawk committed
633
        mavlink_message_t beat;
lm's avatar
lm committed
634
        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
635 636
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
637 638
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
639 640
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
641
        memset(&auth, 0, sizeof(auth));
642
        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
643 644 645
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
646 647 648 649 650 651 652 653 654
}

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

655 656 657 658 659 660 661 662 663
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

664 665 666 667
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
668
    if (m_authEnabled != enable) {
669 670 671 672 673
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

674 675
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
676
    if (enabled != m_paramGuardEnabled) {
677 678 679 680 681
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

682 683
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
684
    if (enabled != m_actionGuardEnabled) {
685 686 687 688 689
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

690 691
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
692
    if (ms != m_paramRetransmissionTimeout) {
693 694 695 696 697 698 699
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
700
    if (ms != m_paramRewriteTimeout) {
701 702 703 704 705
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

706 707
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
708
    if (ms != m_actionRetransmissionTimeout) {
709 710 711 712 713
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
714 715
void MAVLinkProtocol::enableLogging(bool enabled)
{
716 717 718
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

719 720 721 722
    if (enabled)
    {
        if (m_logfile && m_logfile->isOpen())
        {
723 724 725
            m_logfile->flush();
            m_logfile->close();
        }
726 727 728 729 730

        if (m_logfile)
        {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
            {
731 732
                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;
733
            }
734
        }
735 736 737 738 739 740 741 742 743 744 745
        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())
            {
746 747 748
                m_logfile->flush();
                m_logfile->close();
            }
749
        }
lm's avatar
lm committed
750 751
    }
    m_loggingEnabled = enabled;
752
    if (changed) emit loggingChanged(enabled);
753 754 755 756
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
757 758
    if (!m_logfile)
    {
759
        m_logfile = new QFile(filename);
760 761 762
    }
    else
    {
763 764 765
        m_logfile->flush();
        m_logfile->close();
    }
766
    m_logfile->setFileName(filename);
767
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
768 769
}

lm's avatar
lm committed
770 771 772
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
773
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
774 775
}

pixhawk's avatar
pixhawk committed
776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
    heartbeatRate = rate;
    heartbeatTimer->setInterval(1000/heartbeatRate);
}

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