MAVLinkProtocol.cc 20.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>
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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
151 152
QString MAVLinkProtocol::getLogfileName()
{
153
    if (m_logfile) {
154
        return m_logfile->fileName();
155
    } else {
156
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
157
    }
pixhawk's avatar
pixhawk committed
158 159
}

pixhawk's avatar
pixhawk committed
160 161 162 163 164 165 166 167
/**
 * 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
 **/
168
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
169
{
170
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
171 172
    mavlink_message_t message;
    mavlink_status_t status;
173

174
    for (int position = 0; position < b.size(); position++) {
175
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed
176

177
        if (decodeState == 1) {
LM's avatar
LM committed
178 179 180 181 182 183 184 185
//#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
186 187 188
#ifdef QGC_PROTOBUF_ENABLED
            if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
            {
189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210
                mavlink_extended_message_t extended_message;

                extended_message.base_msg = message;

                // read extended header
                uint8_t* payload = reinterpret_cast<uint8_t*>(message.payload64);
                memcpy(&extended_message.extended_payload_len, payload + 3, 4);

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

                if (protobufManager.cacheFragment(extended_message))
                {
                    std::tr1::shared_ptr<google::protobuf::Message> protobuf_msg;

                    if (protobufManager.getMessage(protobuf_msg))
                    {
                        emit extendedMessageReceived(link, protobuf_msg);
                    }
                }
211 212 213 214

                position += extended_message.extended_payload_len;

                continue;
215 216 217
            }
#endif

pixhawk's avatar
pixhawk committed
218
            // Log data
219
            if (m_loggingEnabled && m_logfile) {
lm's avatar
lm committed
220
                const int len = MAVLINK_MAX_PACKET_LEN+sizeof(quint64);
221 222
                uint8_t buf[len];
                quint64 time = QGC::groundTimeUsecs();
223
                memcpy(buf, (void*)&time, sizeof(quint64));
224
                // Write message to buffer
225
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
226
                QByteArray b((const char*)buf, len);
227
                if(m_logfile->write(b) < static_cast<qint64>(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))) {
228 229 230 231
                    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
232 233
            }

pixhawk's avatar
pixhawk committed
234 235 236
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
237

pixhawk's avatar
pixhawk committed
238 239 240
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
241
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
pixhawk's avatar
pixhawk committed
242 243 244 245 246 247
                // 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
248
                // Check if the UAS has the same id like this system
249
                if (message.sysid == getSystemId()) {
250
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
251 252
                }

253 254 255 256
                // 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
257
                // First create new UAS object
258 259
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
260 261
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
262
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
263 264

                // Check if the UAS has a different protocol version
265
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION)) {
pixhawk's avatar
pixhawk committed
266
                    // Bring up dialog to inform user
267
                    if (!versionMismatchIgnore) {
268
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
269
                                                   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));
270 271
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
272 273 274 275 276

                    // Ignore this message and continue gracefully
                    continue;
                }

277 278
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
pixhawk's avatar
pixhawk committed
279
            }
280 281

            // Only count message if UAS exists for this message
282
            if (uas != NULL) {
283 284 285 286 287
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
288
                if (lastIndex[message.sysid][message.compid] == -1) {
289
                    lastIndex[message.sysid][message.compid] = message.seq;
290
                } else {
Mariano Lizarraga's avatar
Mariano Lizarraga committed
291
                    // TODO: This if-else block can (should) be greatly simplified
292
                    if (lastIndex[message.sysid][message.compid] == 255) {
lm's avatar
lm committed
293
                        lastIndex[message.sysid][message.compid] = 0;
294
                    } else {
lm's avatar
lm committed
295 296
                        lastIndex[message.sysid][message.compid]++;
                    }
297 298 299

                    int safeguard = 0;
                    //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
300 301
                    while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 255) {
                        if (lastIndex[message.sysid][message.compid] == 255) {
302
                            lastIndex[message.sysid][message.compid] = 0;
303
                        } else {
304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319
                            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
320
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0)) {
321 322 323 324 325 326 327
                    // 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
328
                    emit receiveLossChanged(message.sysid, receiveLoss);
Mariano Lizarraga's avatar
Mariano Lizarraga committed
329
                    //qDebug() << "LOSSCHANGED" << message.sysid<<" "<<receiveLoss;
lm's avatar
lm committed
330 331
                }

332 333 334 335
                // 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);
336 337

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

                    // Emit message on all links that are currently connected
343
                    foreach (LinkInterface* currLink, links) {
344 345 346 347 348
                        // 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
//    receiveMutex.unlock();
pixhawk's avatar
pixhawk committed
353 354 355 356 357 358 359 360 361 362
}

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

/**
 * @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];
404
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
405 406
    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
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
    // If link is connected
410
    if (link->isConnected()) {
pixhawk's avatar
pixhawk committed
411 412 413 414 415 416 417 418 419 420 421 422
        // 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()
{
423
    if (m_heartbeatsEnabled) {
pixhawk's avatar
pixhawk committed
424
        mavlink_message_t beat;
lm's avatar
lm committed
425
        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
426 427
        sendMessage(beat);
    }
James Goppert's avatar
James Goppert committed
428 429 430 431 432 433 434 435
    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
436 437 438 439 440 441 442 443 444
}

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

445 446 447 448 449 450 451 452 453
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

454 455 456 457
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
458
    if (m_authEnabled != enable) {
459 460 461 462 463
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

464 465
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
466
    if (enabled != m_paramGuardEnabled) {
467 468 469 470 471
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

472 473
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
474
    if (enabled != m_actionGuardEnabled) {
475 476 477 478 479
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

480 481
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
482
    if (ms != m_paramRetransmissionTimeout) {
483 484 485 486 487 488 489
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
490
    if (ms != m_paramRewriteTimeout) {
491 492 493 494 495
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

496 497
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
498
    if (ms != m_actionRetransmissionTimeout) {
499 500 501 502 503
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
504 505
void MAVLinkProtocol::enableLogging(bool enabled)
{
506 507 508
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

509 510
    if (enabled) {
        if (m_logfile && m_logfile->isOpen()) {
511 512 513
            m_logfile->flush();
            m_logfile->close();
        }
514 515
        if (m_logfile) {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append)) {
516 517
                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;
518
            }
519
        }
520 521 522
    } else if (!enabled) {
        if (m_logfile) {
            if (m_logfile->isOpen()) {
523 524 525
                m_logfile->flush();
                m_logfile->close();
            }
526 527 528
            delete m_logfile;
            m_logfile = NULL;
        }
lm's avatar
lm committed
529 530
    }
    m_loggingEnabled = enabled;
531
    if (changed) emit loggingChanged(enabled);
532 533 534 535
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
536
    if (!m_logfile) {
537
        m_logfile = new QFile(filename);
538
    } else {
539 540 541
        m_logfile->flush();
        m_logfile->close();
    }
542
    m_logfile->setFileName(filename);
543
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
544 545
}

lm's avatar
lm committed
546 547 548
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
549
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
550 551
}

pixhawk's avatar
pixhawk committed
552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567
/**
 * 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;
}