MAVLinkProtocol.cc 24.5 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
#include <QSettings>
18
#include <QStandardPaths>
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
Q_DECLARE_METATYPE(mavlink_message_t)
37

pixhawk's avatar
pixhawk committed
38 39 40 41 42
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
MAVLinkProtocol::MAVLinkProtocol() :
43
    heartbeatTimer(NULL),
44
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
45
    m_heartbeatsEnabled(true),
46 47 48 49 50 51 52 53 54 55 56
    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),
57 58
    systemId(QGC::defaultSystemId),
    _should_exit(false)
pixhawk's avatar
pixhawk committed
59
{
60 61
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

62
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
63
    loadSettings();
Lorenz Meier's avatar
Lorenz Meier committed
64
    moveToThread(this);
65 66 67 68 69

    // 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.
70 71 72 73
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
74 75 76
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
77

Lorenz Meier's avatar
Lorenz Meier committed
78 79
    start(QThread::HighPriority);

lm's avatar
lm committed
80
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
81 82
}

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

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

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
107 108
    if (temp > 0 && temp < 256)
    {
109 110
        systemId = temp;
    }
111

112 113 114 115
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

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

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

    // Tell the thread to exit
167
    _should_exit = true;
Lorenz Meier's avatar
Lorenz Meier committed
168 169 170 171 172 173 174 175 176 177
    // Wait for it to exit
    wait();
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkProtocol::run()
{
178 179 180 181 182 183 184 185 186
    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()) {
187
            delete heartbeatTimer;
188 189 190 191 192 193 194
            qDebug() << "MAVLINK WORKER DONE!";
            return;
        }

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

pixhawk's avatar
pixhawk committed
197 198
QString MAVLinkProtocol::getLogfileName()
{
199 200
    if (m_logfile)
    {
201
        return m_logfile->fileName();
202 203 204
    }
    else
    {
205
        return QStandardPaths::writableLocation(QStandardPaths::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
206
    }
pixhawk's avatar
pixhawk committed
207 208
}

209 210 211 212 213 214 215 216 217 218
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;
}

219 220 221 222 223 224 225 226 227 228
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
229
            link->writeBytes(init, sizeof(init));
230
            const char* cmd = "sh /etc/init.d/rc.usb\n";
231 232 233 234 235 236
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 4);
        }
    }
}

pixhawk's avatar
pixhawk committed
237 238 239 240 241 242 243
/**
 * 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
 **/
244
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
245
{
246
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
247 248
    mavlink_message_t message;
    mavlink_status_t status;
249

250 251 252
    // Cache the link ID for common use.
    int linkId = link->getId();

253
    static int mavlink09Count = 0;
254
    static int nonmavlinkCount = 0;
255
    static bool decodedFirstPacket = false;
256
    static bool warnedUser = false;
257 258
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
259

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

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
265
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
266
        {
267
            warnedUser = true;
268 269
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
270
            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.");
271
        }
pixhawk's avatar
pixhawk committed
272

273 274 275
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
276
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
277
            {
278
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
279 280 281 282 283 284 285 286 287 288 289 290
                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.");
                }
            }
        }
291 292
        if (decodeState == 1)
        {
293
            decodedFirstPacket = true;
294 295 296 297 298 299 300 301 302 303 304 305 306 307

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

308 309 310 311 312 313 314 315 316 317
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);

                emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rstatus.rssi, rstatus.remrssi,
                    rstatus.txbuf, rstatus.noise, rstatus.remnoise);
            }

pixhawk's avatar
pixhawk committed
318
            // Log data
319 320
            if (m_loggingEnabled && m_logfile)
            {
321 322 323 324 325 326 327 328 329 330 331 332 333 334 335
                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.
336
                QByteArray b((const char*)buf, len);
Lorenz Meier's avatar
Lorenz Meier committed
337
                if(m_logfile->write(b) != len)
338
                {
339
                    // If there's an error logging data, raise an alert and stop logging.
340 341 342
                    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
343 344
            }

pixhawk's avatar
pixhawk committed
345 346 347
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
348

pixhawk's avatar
pixhawk committed
349 350 351
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
352 353
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
354 355 356 357 358 359
                // 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
360
                // Check if the UAS has the same id like this system
361 362
                if (message.sysid == getSystemId())
                {
363
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
364 365
                }

366 367 368 369
                // 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
370
                // First create new UAS object
371 372
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
373 374
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
375
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
376 377

                // Check if the UAS has a different protocol version
378 379
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
380
                    // Bring up dialog to inform user
381 382
                    if (!versionMismatchIgnore)
                    {
383
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
384
                                                   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));
385 386
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
387 388 389 390 391

                    // Ignore this message and continue gracefully
                    continue;
                }

392 393
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
394

pixhawk's avatar
pixhawk committed
395
            }
396 397

            // Only count message if UAS exists for this message
398 399
            if (uas != NULL)
            {
400

401
                // Increase receive counter
402 403
                totalReceiveCounter[linkId]++;
                currReceiveCounter[linkId]++;
404

405 406 407 408
                // Determine what the next expected sequence number is, accounting for
                // never having seen a message for this system/component pair.
                int lastSeq = lastIndex[message.sysid][message.compid];
                int expectedSeq = (lastSeq == -1) ? message.seq : (lastSeq + 1);
409

410 411
                // And if we didn't encounter that sequence number, record the error
                if (message.seq != expectedSeq)
412
                {
413 414 415 416 417

                    // Determine how many messages were skipped
                    int lostMessages = message.seq - expectedSeq;

                    // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
418 419 420 421
                    if (lostMessages < 0)
                    {
                        lostMessages = 0;
                    }
422 423

                    // And log how many were lost for all time and just this timestep
424 425
                    totalLossCounter[linkId] += lostMessages;
                    currLossCounter[linkId] += lostMessages;
426
                }
427

428 429
                // And update the last sequence number for this system/component pair
                lastIndex[message.sysid][message.compid] = expectedSeq;
430

431
                // Update on every 32th packet
432
                if ((totalReceiveCounter[linkId] & 0x1F) == 0)
433
                {
434 435
                    // Calculate new loss ratio
                    // Receive loss
436
                    float receiveLoss = (double)currLossCounter[linkId]/(double)(currReceiveCounter[linkId]+currLossCounter[linkId]);
437
                    receiveLoss *= 100.0f;
438 439
                    currLossCounter[linkId] = 0;
                    currReceiveCounter[linkId] = 0;
pixhawk's avatar
pixhawk committed
440
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
441 442
                }

443 444 445 446
                // 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);
447 448

                // Multiplex message if enabled
449 450
                if (m_multiplexingEnabled)
                {
451 452 453 454
                    // Get all links connected to this unit
                    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

                    // Emit message on all links that are currently connected
455 456
                    foreach (LinkInterface* currLink, links)
                    {
457 458
                        // Only forward this message to the other links,
                        // not the link the message was received on
Lorenz Meier's avatar
Lorenz Meier committed
459
                        if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
460 461
                    }
                }
462
            }
pixhawk's avatar
pixhawk committed
463 464 465 466 467 468 469 470 471 472 473 474
        }
    }
}

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

475
/** @return System id of this application */
476
int MAVLinkProtocol::getSystemId()
477
{
478 479 480 481 482 483
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
484 485 486
}

/** @return Component id of this application */
487
int MAVLinkProtocol::getComponentId()
488
{
489
    return QGC::defaultComponentId;
490 491
}

pixhawk's avatar
pixhawk committed
492 493 494 495 496 497 498 499 500 501
/**
 * @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;
502 503
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
504
        sendMessage(*i, message);
505
//        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
506 507 508 509 510 511 512 513 514 515
    }
}

/**
 * @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
516
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
517
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
518 519
    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
520
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
521
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
522
    // If link is connected
523 524
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
525 526 527 528 529
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552
/**
 * @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
553 554 555 556 557 558 559
/**
 * 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
560 561
    if (m_heartbeatsEnabled)
    {
pixhawk's avatar
pixhawk committed
562
        mavlink_message_t beat;
lm's avatar
lm committed
563
        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
564 565
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
566 567
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
568 569
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
570
        memset(&auth, 0, sizeof(auth));
571
        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
572 573 574
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
575 576 577 578 579 580 581 582 583
}

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

584 585 586 587 588 589 590 591 592
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

593 594 595 596
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
597
    if (m_authEnabled != enable) {
598 599 600 601 602
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

603 604
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
605
    if (enabled != m_paramGuardEnabled) {
606 607 608 609 610
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

611 612
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
613
    if (enabled != m_actionGuardEnabled) {
614 615 616 617 618
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

619 620
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
621
    if (ms != m_paramRetransmissionTimeout) {
622 623 624 625 626 627 628
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
629
    if (ms != m_paramRewriteTimeout) {
630 631 632 633 634
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

635 636
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
637
    if (ms != m_actionRetransmissionTimeout) {
638 639 640 641 642
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
643 644
void MAVLinkProtocol::enableLogging(bool enabled)
{
645 646 647
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

648 649 650 651
    if (enabled)
    {
        if (m_logfile && m_logfile->isOpen())
        {
652 653 654
            m_logfile->flush();
            m_logfile->close();
        }
655 656 657 658 659

        if (m_logfile)
        {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
            {
660 661
                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;
662
            }
663
        }
664 665 666 667 668 669 670 671 672 673 674
        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())
            {
675 676 677
                m_logfile->flush();
                m_logfile->close();
            }
678
        }
lm's avatar
lm committed
679 680
    }
    m_loggingEnabled = enabled;
681
    if (changed) emit loggingChanged(enabled);
682 683 684 685
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
686 687
    if (!m_logfile)
    {
688
        m_logfile = new QFile(filename);
689 690 691
    }
    else
    {
692 693 694
        m_logfile->flush();
        m_logfile->close();
    }
695
    m_logfile->setFileName(filename);
696
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
697 698
}

lm's avatar
lm committed
699 700 701
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
702
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
703 704
}

pixhawk's avatar
pixhawk committed
705 706 707 708 709 710 711 712
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
    heartbeatRate = rate;
713
    heartbeatTimer->setInterval(1000/heartbeatRate);
pixhawk's avatar
pixhawk committed
714 715 716 717 718 719 720
}

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