MAVLinkProtocol.cc 19.3 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 21 22 23 24

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

/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
MAVLinkProtocol::MAVLinkProtocol() :
39 40 41 42 43 44 45 46 47 48 49 50 51 52 53
    heartbeatTimer(new QTimer(this)),
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    m_heartbeatsEnabled(false),
    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
54
{
55
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
56 57
    loadSettings();
    //start(QThread::LowPriority);
pixhawk's avatar
pixhawk committed
58 59 60
    // 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
61 62
    totalReceiveCounter = 0;
    totalLossCounter = 0;
63 64
    currReceiveCounter = 0;
    currLossCounter = 0;
65 66
    for (int i = 0; i < 256; i++) {
        for (int j = 0; j < 256; j++) {
lm's avatar
lm committed
67 68 69
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
70 71

    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
72 73
}

74 75 76 77 78 79
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.sync();
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
80
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool());
81 82
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
83 84

    // Only set logfile if there is a name present in settings
85
    if (settings.contains("LOGFILE_NAME") && m_logfile == NULL) {
86
        m_logfile = new QFile(settings.value("LOGFILE_NAME").toString());
87
    } else if (m_logfile == NULL) {
88 89
        m_logfile = new QFile(QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink");
    }
90 91
    // Enable logging
    enableLogging(settings.value("LOGGING_ENABLED", m_loggingEnabled).toBool());
92 93 94

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

99 100 101 102
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

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

pixhawk's avatar
pixhawk committed
138 139
MAVLinkProtocol::~MAVLinkProtocol()
{
140
    storeSettings();
141 142
    if (m_logfile) {
        if (m_logfile->isOpen()) {
143 144 145
            m_logfile->flush();
            m_logfile->close();
        }
pixhawk's avatar
pixhawk committed
146 147
        delete m_logfile;
    }
pixhawk's avatar
pixhawk committed
148 149 150 151 152 153
}



void MAVLinkProtocol::run()
{
lm's avatar
lm committed
154
    exec();
pixhawk's avatar
pixhawk committed
155 156
}

pixhawk's avatar
pixhawk committed
157 158
QString MAVLinkProtocol::getLogfileName()
{
159
    if (m_logfile) {
160
        return m_logfile->fileName();
161
    } else {
162
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
163
    }
pixhawk's avatar
pixhawk committed
164 165
}

pixhawk's avatar
pixhawk committed
166 167 168 169 170 171 172 173
/**
 * 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
 **/
174
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
175 176 177 178
{
    receiveMutex.lock();
    mavlink_message_t message;
    mavlink_status_t status;
179
    for (int position = 0; position < b.size(); position++) {
180
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed
181

182
        if (decodeState == 1) {
LM's avatar
LM committed
183 184 185 186 187 188 189 190
//#ifdef MAVLINK_MESSAGE_LENGTHS
//	    const uint8_t message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
//	    if (message.msgid >= sizeof(message_lengths) ||
//		message.len != message_lengths[message.msgid]) {
//                    qDebug() << "MAVLink message " << message.msgid << " length incorrect (was " << message.len << " expected " << message_lengths[message.msgid] << ")";
//		    continue;
//	    }
//#endif
pixhawk's avatar
pixhawk committed
191
            // Log data
192
            if (m_loggingEnabled && m_logfile) {
lm's avatar
lm committed
193
                const int len = MAVLINK_MAX_PACKET_LEN+sizeof(quint64);
194 195
                uint8_t buf[len];
                quint64 time = QGC::groundTimeUsecs();
196
                memcpy(buf, (void*)&time, sizeof(quint64));
197
                // Write message to buffer
198
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
199
                QByteArray b((const char*)buf, len);
200
                if(m_logfile->write(b) < static_cast<qint64>(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))) {
201 202 203 204
                    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
205 206
            }

pixhawk's avatar
pixhawk committed
207 208 209 210 211 212
            // 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
213
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
pixhawk's avatar
pixhawk committed
214 215 216 217 218 219
                // 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
220
                // Check if the UAS has the same id like this system
221
                if (message.sysid == getSystemId()) {
222
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
223 224
                }

225 226 227 228
                // 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
229
                // First create new UAS object
230 231
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
232 233
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
234
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
235 236

                // Check if the UAS has a different protocol version
237
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION)) {
pixhawk's avatar
pixhawk committed
238
                    // Bring up dialog to inform user
239
                    if (!versionMismatchIgnore) {
240
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
241
                                                   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));
242 243
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
244 245 246 247 248

                    // Ignore this message and continue gracefully
                    continue;
                }

249 250
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
pixhawk's avatar
pixhawk committed
251
            }
252 253

            // Only count message if UAS exists for this message
254
            if (uas != NULL) {
255 256 257 258 259
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
260
                if (lastIndex[message.sysid][message.compid] == -1) {
261
                    lastIndex[message.sysid][message.compid] = message.seq;
262
                } else {
Mariano Lizarraga's avatar
Mariano Lizarraga committed
263
                    // TODO: This if-else block can (should) be greatly simplified
264
                    if (lastIndex[message.sysid][message.compid] == 255) {
lm's avatar
lm committed
265
                        lastIndex[message.sysid][message.compid] = 0;
266
                    } else {
lm's avatar
lm committed
267 268
                        lastIndex[message.sysid][message.compid]++;
                    }
269 270 271

                    int safeguard = 0;
                    //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
272 273
                    while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 255) {
                        if (lastIndex[message.sysid][message.compid] == 255) {
274
                            lastIndex[message.sysid][message.compid] = 0;
275
                        } else {
276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291
                            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
292
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0)) {
293 294 295 296 297 298 299
                    // 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
300
                    emit receiveLossChanged(message.sysid, receiveLoss);
Mariano Lizarraga's avatar
Mariano Lizarraga committed
301
                    //qDebug() << "LOSSCHANGED" << message.sysid<<" "<<receiveLoss;
lm's avatar
lm committed
302 303
                }

304 305 306 307
                // 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);
308 309

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

                    // Emit message on all links that are currently connected
315
                    foreach (LinkInterface* currLink, links) {
316 317 318 319 320
                        // Only forward this message to the other links,
                        // not the link the message was received on
                        if (currLink != link) sendMessage(currLink, message);
                    }
                }
321
            }
pixhawk's avatar
pixhawk committed
322 323 324 325 326 327 328 329 330 331 332 333 334
        }
    }
    receiveMutex.unlock();
}

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

335
/** @return System id of this application */
336
int MAVLinkProtocol::getSystemId()
337
{
338 339 340 341 342 343
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
344 345 346
}

/** @return Component id of this application */
347
int MAVLinkProtocol::getComponentId()
348
{
349
    return QGC::defaultComponentId;
350 351
}

pixhawk's avatar
pixhawk committed
352 353 354 355 356 357 358 359 360 361
/**
 * @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;
362
    for (i = links.begin(); i != links.end(); ++i) {
pixhawk's avatar
pixhawk committed
363
        sendMessage(*i, message);
364
        //qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
365 366 367 368 369 370 371 372 373 374 375
    }
}

/**
 * @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];
376 377
    // 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
378
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
379
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
380
    // If link is connected
381
    if (link->isConnected()) {
pixhawk's avatar
pixhawk committed
382 383 384 385 386 387 388 389 390 391 392 393
        // 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()
{
394
    if (m_heartbeatsEnabled) {
pixhawk's avatar
pixhawk committed
395
        mavlink_message_t beat;
lm's avatar
lm committed
396
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
pixhawk's avatar
pixhawk committed
397 398
        sendMessage(beat);
    }
James Goppert's avatar
James Goppert committed
399 400 401 402 403 404 405 406
    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
407 408 409 410 411 412 413 414 415
}

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

416 417 418 419 420 421 422 423 424
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

425 426 427 428
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
429
    if (m_authEnabled != enable) {
430 431 432 433 434
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

435 436
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
437
    if (enabled != m_paramGuardEnabled) {
438 439 440 441 442
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

443 444
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
445
    if (enabled != m_actionGuardEnabled) {
446 447 448 449 450
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

451 452
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
453
    if (ms != m_paramRetransmissionTimeout) {
454 455 456 457 458 459 460
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
461
    if (ms != m_paramRewriteTimeout) {
462 463 464 465 466
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

467 468
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
469
    if (ms != m_actionRetransmissionTimeout) {
470 471 472 473 474
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
475 476
void MAVLinkProtocol::enableLogging(bool enabled)
{
477 478 479
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

480 481
    if (enabled) {
        if (m_logfile && m_logfile->isOpen()) {
482 483 484
            m_logfile->flush();
            m_logfile->close();
        }
485 486
        if (m_logfile) {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append)) {
487 488
                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;
489
            }
490
        }
491 492 493
    } else if (!enabled) {
        if (m_logfile) {
            if (m_logfile->isOpen()) {
494 495 496
                m_logfile->flush();
                m_logfile->close();
            }
497 498 499
            delete m_logfile;
            m_logfile = NULL;
        }
lm's avatar
lm committed
500 501
    }
    m_loggingEnabled = enabled;
502
    if (changed) emit loggingChanged(enabled);
503 504 505 506
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
507
    if (!m_logfile) {
508
        m_logfile = new QFile(filename);
509
    } else {
510 511 512
        m_logfile->flush();
        m_logfile->close();
    }
513
    m_logfile->setFileName(filename);
514
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
515 516
}

lm's avatar
lm committed
517 518 519
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
520
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
521 522
}

pixhawk's avatar
pixhawk committed
523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538
/**
 * 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;
}