MAVLinkProtocol.cc 19.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 18
#include <QSettings>
#include <QDesktopServices>
pixhawk's avatar
pixhawk committed
19

20
//#include "MG.h"
pixhawk's avatar
pixhawk committed
21 22 23 24 25
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
26 27
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
28
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
29 30
#include "configuration.h"
#include "LinkManager.h"
31
//#include "MainWindow.h"
32 33
#include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
34
#include "QGC.h"
pixhawk's avatar
pixhawk committed
35 36 37 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() :
        heartbeatTimer(new QTimer(this)),
        heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
lm's avatar
lm committed
43
        m_heartbeatsEnabled(false),
44 45
        m_multiplexingEnabled(false),
        m_authEnabled(false),
lm's avatar
lm committed
46
        m_loggingEnabled(false),
47
        m_logfile(NULL),
lm's avatar
lm committed
48
        m_enable_version_check(true),
49 50 51
        m_paramRetransmissionTimeout(350),
        m_paramRewriteTimeout(500),
        m_paramGuardEnabled(true),
52 53
        m_actionGuardEnabled(false),
        m_actionRetransmissionTimeout(100),
54 55
        versionMismatchIgnore(false),
        systemId(QGC::defaultSystemId)
pixhawk's avatar
pixhawk committed
56
{
57
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
58 59
    loadSettings();
    //start(QThread::LowPriority);
pixhawk's avatar
pixhawk committed
60 61 62
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);
lm's avatar
lm committed
63 64
    totalReceiveCounter = 0;
    totalLossCounter = 0;
65 66
    currReceiveCounter = 0;
    currLossCounter = 0;
lm's avatar
lm committed
67 68 69 70 71 72 73
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
74 75

    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
76 77
}

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

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

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

107 108 109 110
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

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

pixhawk's avatar
pixhawk committed
147 148
MAVLinkProtocol::~MAVLinkProtocol()
{
149
    storeSettings();
pixhawk's avatar
pixhawk committed
150 151
    if (m_logfile)
    {
152 153 154 155 156
        if (m_logfile->isOpen())
        {
            m_logfile->flush();
            m_logfile->close();
        }
pixhawk's avatar
pixhawk committed
157 158
        delete m_logfile;
    }
pixhawk's avatar
pixhawk committed
159 160 161 162 163 164
}



void MAVLinkProtocol::run()
{
lm's avatar
lm committed
165
    exec();
pixhawk's avatar
pixhawk committed
166 167
}

pixhawk's avatar
pixhawk committed
168 169
QString MAVLinkProtocol::getLogfileName()
{
170 171 172 173 174 175
    if (m_logfile)
    {
        return m_logfile->fileName();
    }
    else
    {
176
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
177
    }
pixhawk's avatar
pixhawk committed
178 179
}

pixhawk's avatar
pixhawk committed
180 181 182 183 184 185 186 187
/**
 * The bytes are copied by calling the LinkInterface::readBytes() method.
 * 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
 **/
188
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
189 190 191 192
{
    receiveMutex.lock();
    mavlink_message_t message;
    mavlink_status_t status;
193
    for (int position = 0; position < b.size(); position++)
pixhawk's avatar
pixhawk committed
194
    {
195
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed
196 197 198

        if (decodeState == 1)
        {
pixhawk's avatar
pixhawk committed
199
            // Log data
200
            if (m_loggingEnabled && m_logfile)
pixhawk's avatar
pixhawk committed
201
            {
lm's avatar
lm committed
202
                const int len = MAVLINK_MAX_PACKET_LEN+sizeof(quint64);
203 204
                uint8_t buf[len];
                quint64 time = QGC::groundTimeUsecs();
205
                memcpy(buf, (void*)&time, sizeof(quint64));
206
                // Write message to buffer
207
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
208
                QByteArray b((const char*)buf, len);
209
                if(m_logfile->write(b) < static_cast<qint64>(MAVLINK_MAX_PACKET_LEN+sizeof(quint64)))
210 211 212 213 214
                {
                    emit protocolStatusMessage(tr("MAVLink Logging failed"), tr("Could not write to file %1, disabling logging.").arg(m_logfile->fileName()));
                    // Stop logging
                    enableLogging(false);
                }
pixhawk's avatar
pixhawk committed
215 216
            }

pixhawk's avatar
pixhawk committed
217 218 219 220 221 222
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
223
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
pixhawk's avatar
pixhawk committed
224 225 226 227 228 229 230
            {
                // 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
231
                // Check if the UAS has the same id like this system
232 233
                if (message.sysid == getSystemId())
                {
234
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
235 236
                }

237 238 239 240
                // 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
241
                // First create new UAS object
242 243
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
244 245
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
246
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
247 248

                // Check if the UAS has a different protocol version
lm's avatar
lm committed
249
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
pixhawk's avatar
pixhawk committed
250 251
                {
                    // Bring up dialog to inform user
252 253 254
                    if (!versionMismatchIgnore)
                    {
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
255
                                                   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));
256 257
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
258 259 260 261 262

                    // Ignore this message and continue gracefully
                    continue;
                }

263 264
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
pixhawk's avatar
pixhawk committed
265
            }
266 267 268

            // Only count message if UAS exists for this message
            if (uas != NULL)
lm's avatar
lm committed
269
            {
270 271 272 273 274 275
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
                if (lastIndex[message.sysid][message.compid] == -1)
lm's avatar
lm committed
276
                {
277
                    lastIndex[message.sysid][message.compid] = message.seq;
lm's avatar
lm committed
278 279
                }
                else
lm's avatar
lm committed
280
                {
Mariano Lizarraga's avatar
Mariano Lizarraga committed
281
                    // TODO: This if-else block can (should) be greatly simplified
lm's avatar
lm committed
282 283 284 285 286 287 288 289
                    if (lastIndex[message.sysid][message.compid] == 255)
                    {
                        lastIndex[message.sysid][message.compid] = 0;
                    }
                    else
                    {
                        lastIndex[message.sysid][message.compid]++;
                    }
290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316

                    int safeguard = 0;
                    //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
                    while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 255)
                    {
                        if (lastIndex[message.sysid][message.compid] == 255)
                        {
                            lastIndex[message.sysid][message.compid] = 0;
                        }
                        else
                        {
                            lastIndex[message.sysid][message.compid]++;
                        }
                        totalLossCounter++;
                        currLossCounter++;
                        safeguard++;
                    }
                }
                //            if (lastIndex.contains(message.sysid))
                //            {
                //                QMap<int, int>* lastCompIndex = lastIndex.value(message.sysid);
                //                if (lastCompIndex->contains(message.compid))
                //                while (lastCompIndex->value(message.compid, 0)+1 )
                //            }
                //if ()

                // If a new loss was detected or we just hit one 128th packet step
lm's avatar
lm committed
317
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0))
318 319 320 321 322 323 324 325
                {
                    // Calculate new loss ratio
                    // Receive loss
                    float receiveLoss = (double)currLossCounter/(double)(currReceiveCounter+currLossCounter);
                    receiveLoss *= 100.0f;
                    // qDebug() << "LOSSCHANGED" << receiveLoss;
                    currLossCounter = 0;
                    currReceiveCounter = 0;
pixhawk's avatar
pixhawk committed
326
                    emit receiveLossChanged(message.sysid, receiveLoss);
Mariano Lizarraga's avatar
Mariano Lizarraga committed
327
                    //qDebug() << "LOSSCHANGED" << message.sysid<<" "<<receiveLoss;
lm's avatar
lm committed
328 329
                }

330 331 332 333
                // 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);
334 335 336 337 338 339 340 341 342 343 344 345 346 347 348

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

                    // Emit message on all links that are currently connected
                    foreach (LinkInterface* currLink, links)
                    {
                        // Only forward this message to the other links,
                        // not the link the message was received on
                        if (currLink != link) sendMessage(currLink, message);
                    }
                }
349
            }
pixhawk's avatar
pixhawk committed
350 351 352 353 354 355 356 357 358 359 360 361 362
        }
    }
    receiveMutex.unlock();
}

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

363
/** @return System id of this application */
364
int MAVLinkProtocol::getSystemId()
365
{
366 367 368 369 370 371
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
372 373 374
}

/** @return Component id of this application */
375
int MAVLinkProtocol::getComponentId()
376
{
377
    return QGC::defaultComponentId;
378 379
}

pixhawk's avatar
pixhawk committed
380 381 382 383 384 385 386 387 388 389 390 391 392
/**
 * @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;
    for (i = links.begin(); i != links.end(); ++i)
    {
        sendMessage(*i, message);
393
        //qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
394 395 396 397 398 399 400 401 402 403 404
    }
}

/**
 * @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
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
405 406
    // Rewriting header to ensure correct link ID is set
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
407
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
408
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426
    // If link is connected
    if (link->isConnected())
    {
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * 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()
{
    if (m_heartbeatsEnabled)
    {
        mavlink_message_t beat;
lm's avatar
lm committed
427
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
pixhawk's avatar
pixhawk committed
428 429
        sendMessage(beat);
    }
430 431 432 433 434 435 436 437 438
    if (m_authEnabled)
    {
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
        if (m_authKey.length() != MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN) m_authKey.resize(MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN);
        strcpy(auth.key, m_authKey.toStdString().c_str());
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
439 440 441 442 443 444 445 446 447
}

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

448 449 450 451 452 453 454 455 456
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

457 458 459 460 461 462 463 464 465 466 467
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
    if (m_authEnabled != enable)
    {
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

468 469 470 471 472 473 474 475 476
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
    if (enabled != m_paramGuardEnabled)
    {
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

477 478 479 480 481 482 483 484 485
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
    if (enabled != m_actionGuardEnabled)
    {
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
    if (ms != m_paramRetransmissionTimeout)
    {
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
    if (ms != m_paramRewriteTimeout)
    {
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

504 505 506 507 508 509 510 511 512
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
    if (ms != m_actionRetransmissionTimeout)
    {
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
513 514
void MAVLinkProtocol::enableLogging(bool enabled)
{
515 516 517 518
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

    if (enabled)
lm's avatar
lm committed
519
    {
520
        if (m_logfile && m_logfile->isOpen())
521 522 523 524
        {
            m_logfile->flush();
            m_logfile->close();
        }
525
        if (m_logfile)
526
        {
527 528
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
            {
529 530
                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;
531
            }
532
        }
lm's avatar
lm committed
533
    }
534
    else if (!enabled)
lm's avatar
lm committed
535
    {
536 537
        if (m_logfile)
        {
538 539 540 541 542
            if (m_logfile->isOpen())
            {
                m_logfile->flush();
                m_logfile->close();
            }
543 544 545
            delete m_logfile;
            m_logfile = NULL;
        }
lm's avatar
lm committed
546 547
    }
    m_loggingEnabled = enabled;
548
    if (changed) emit loggingChanged(enabled);
549 550 551 552
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
553 554 555 556 557 558 559 560 561
    if (!m_logfile)
    {
        m_logfile = new QFile(filename);
    }
    else
    {
        m_logfile->flush();
        m_logfile->close();
    }
562
    m_logfile->setFileName(filename);
563
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
564 565
}

lm's avatar
lm committed
566 567 568
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
569
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
570 571
}

pixhawk's avatar
pixhawk committed
572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587
/**
 * 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;
}