MAVLinkProtocol.cc 26.8 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>
16
#include <QSettings>
17
#include <QStandardPaths>
18
#include <QtEndian>
19
#include <QMetaType>
pixhawk's avatar
pixhawk committed
20 21 22 23 24 25 26 27

#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
#include "configuration.h"
#include "LinkManager.h"
28 29
#include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
30
#include "QGC.h"
Don Gagne's avatar
Don Gagne committed
31
#include "QGCApplication.h"
32
#include "QGCLoggingCategory.h"
pixhawk's avatar
pixhawk committed
33

34
Q_DECLARE_METATYPE(mavlink_message_t)
35
IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol)
36
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
37

Don Gagne's avatar
Don Gagne committed
38 39 40
const char* MAVLinkProtocol::_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file
const char* MAVLinkProtocol::_logFileExtension = "mavlink";             ///< Extension for log files

pixhawk's avatar
pixhawk committed
41 42 43 44
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
45 46
MAVLinkProtocol::MAVLinkProtocol(QObject* parent) :
    QGCSingleton(parent),
47 48 49 50 51 52 53 54 55
    m_multiplexingEnabled(false),
    m_authEnabled(false),
    m_enable_version_check(true),
    m_paramRetransmissionTimeout(350),
    m_paramRewriteTimeout(500),
    m_paramGuardEnabled(true),
    m_actionGuardEnabled(false),
    m_actionRetransmissionTimeout(100),
    versionMismatchIgnore(false),
56
    systemId(QGC::defaultSystemId),
Don Gagne's avatar
Don Gagne committed
57 58
    _logSuspendError(false),
    _logSuspendReplay(false),
59
    _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)),
60 61 62
    _linkMgr(LinkManager::instance()),
    _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    _heartbeatsEnabled(true)
pixhawk's avatar
pixhawk committed
63
{
64
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
Don Gagne's avatar
Don Gagne committed
65
    
66
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
67
    loadSettings();
68 69 70 71 72

    // 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.
73 74 75 76
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
77 78 79
            lastIndex[i][j] = -1;
        }
    }
80 81 82 83
    
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(&_heartbeatTimer, &QTimer::timeout, this, &MAVLinkProtocol::sendHeartbeat);
    _heartbeatTimer.start(1000/_heartbeatRate);
Lorenz Meier's avatar
Lorenz Meier committed
84

85 86 87
    connect(this, &MAVLinkProtocol::protocolStatusMessage, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread);
    connect(this, &MAVLinkProtocol::saveTempFlightDataLog, qgcApp(), &QGCApplication::saveTempFlightDataLogOnMainThread);

lm's avatar
lm committed
88
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
89 90
}

91 92 93 94 95 96 97
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    
    _closeLogFile();
}

98 99 100 101 102
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
103
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", _heartbeatsEnabled).toBool());
104 105
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
106 107 108

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

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

118 119 120 121 122 123 124
    // 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();
125 126 127 128 129 130 131 132
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
133
    settings.setValue("HEARTBEATS_ENABLED", _heartbeatsEnabled);
134 135
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
136
    settings.setValue("GCS_SYSTEM_ID", systemId);
137 138
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
139 140 141 142
    // 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);
143 144 145
    settings.endGroup();
}

146 147 148 149 150 151 152 153 154 155
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;
}

156
void MAVLinkProtocol::linkConnected(void)
157 158
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
159
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
160
    
161 162 163 164 165 166 167 168 169 170 171 172 173
    _linkStatusChanged(link, true);
}

void MAVLinkProtocol::linkDisconnected(void)
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
    Q_ASSERT(link);
    
    _linkStatusChanged(link, false);
}

void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
{
174
    qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected;
175
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
176 177
    
    if (connected) {
178 179 180 181 182 183
        foreach (SharedLinkInterface sharedLink, _connectedLinks) {
            Q_ASSERT(sharedLink.data() != link);
        }
        
        // Use the same shared pointer as LinkManager
        _connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link));
Don Gagne's avatar
Don Gagne committed
184 185 186 187 188 189 190 191 192 193 194 195 196 197 198
        
        if (_connectedLinks.count() == 1) {
            // This is the first link, we need to start logging
            _startLogging();
        }
        
        // Send command to start MAVLink
        // XXX hacky but safe
        // Start NSH
        const char init[] = {0x0d, 0x0d, 0x0d};
        link->writeBytes(init, sizeof(init));
        const char* cmd = "sh /etc/init.d/rc.usb\n";
        link->writeBytes(cmd, strlen(cmd));
        link->writeBytes(init, 4);
    } else {
199 200 201 202 203 204 205 206
        bool found = false;
        for (int i=0; i<_connectedLinks.count(); i++) {
            if (_connectedLinks[i].data() == link) {
                found = true;
                _connectedLinks.removeAt(i);
                break;
            }
        }
207
        Q_UNUSED(found);
208
        Q_ASSERT(found);
Don Gagne's avatar
Don Gagne committed
209 210 211 212 213 214
        
        if (_connectedLinks.count() == 0) {
            // Last link is gone, close out logging
            _stopLogging();
        }
    }
215 216
}

pixhawk's avatar
pixhawk committed
217 218 219 220 221 222 223
/**
 * 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
 **/
224
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
225
{
226
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
227 228
    mavlink_message_t message;
    mavlink_status_t status;
229

230 231 232
    // Cache the link ID for common use.
    int linkId = link->getId();

233
    static int mavlink09Count = 0;
234
    static int nonmavlinkCount = 0;
235
    static bool decodedFirstPacket = false;
236
    static bool warnedUser = false;
237 238
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
239

240
    // FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
241
    for (int position = 0; position < b.size(); position++) {
242
        unsigned int decodeState = mavlink_parse_char(linkId, (uint8_t)(b[position]), &message, &status);
243 244

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
245
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
246
        {
247
            warnedUser = true;
248 249
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
250 251 252 253
            emit protocolStatusMessage(tr("MAVLink Protocol"), tr("There is a 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."));
254
        }
pixhawk's avatar
pixhawk committed
255

256 257 258
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
259
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
260
            {
261
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
262 263 264 265 266 267 268 269
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
270 271
                    emit protocolStatusMessage(tr("MAVLink Protocol"), tr("There is a MAVLink Version or Baud Rate Mismatch. "
                                                                          "Please check if the baud rates of QGroundControl and your autopilot are the same."));
272 273 274
                }
            }
        }
275 276
        if (decodeState == 1)
        {
277
            decodedFirstPacket = true;
278 279 280 281 282 283 284 285 286 287 288 289 290 291

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

292 293 294 295 296 297 298 299 300 301
            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
302
            // Log data
Don Gagne's avatar
Don Gagne committed
303
            
Don Gagne's avatar
Don Gagne committed
304
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
305 306 307 308 309 310 311 312 313 314 315 316 317 318 319
                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.
320
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
321
                if(_tempLogFile.write(b) != len)
322
                {
323
                    // If there's an error logging data, raise an alert and stop logging.
324
                    emit protocolStatusMessage(tr("MAVLink Protocol"), tr("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName()));
Don Gagne's avatar
Don Gagne committed
325 326
                    _stopLogging();
                    _logSuspendError = true;
327
                }
pixhawk's avatar
pixhawk committed
328 329
            }

pixhawk's avatar
pixhawk committed
330 331 332
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
333

pixhawk's avatar
pixhawk committed
334 335 336
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
337 338
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
339 340 341 342 343 344
                // 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
345
                // Check if the UAS has the same id like this system
346 347
                if (message.sysid == getSystemId())
                {
348
                    emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
349 350
                }

351 352 353 354
                // 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
355
                // First create new UAS object
356 357
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
358 359
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
360
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
361 362

                // Check if the UAS has a different protocol version
363 364
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
365
                    // Bring up dialog to inform user
366 367
                    if (!versionMismatchIgnore)
                    {
368 369 370
                        emit protocolStatusMessage(tr("MAVLink Protocol"), tr("The MAVLink protocol version on the MAV and QGroundControl mismatch! "
                                                                              "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));
371 372
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
373 374 375 376 377

                    // Ignore this message and continue gracefully
                    continue;
                }

378 379
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
380

pixhawk's avatar
pixhawk committed
381
            }
382

383 384 385
            // Increase receive counter
            totalReceiveCounter[linkId]++;
            currReceiveCounter[linkId]++;
386

387 388 389 390
            // 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);
391

392 393 394
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
395

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

399 400 401 402 403
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
404

405 406 407 408
                // And log how many were lost for all time and just this timestep
                totalLossCounter[linkId] += lostMessages;
                currLossCounter[linkId] += lostMessages;
            }
409

410 411
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
412

413 414 415 416 417 418 419 420 421 422 423
            // Update on every 32th packet
            if ((totalReceiveCounter[linkId] & 0x1F) == 0)
            {
                // Calculate new loss ratio
                // Receive loss
                float receiveLoss = (double)currLossCounter[linkId]/(double)(currReceiveCounter[linkId]+currLossCounter[linkId]);
                receiveLoss *= 100.0f;
                currLossCounter[linkId] = 0;
                currReceiveCounter[linkId] = 0;
                emit receiveLossChanged(message.sysid, receiveLoss);
            }
424

425 426 427 428
            // 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);
lm's avatar
lm committed
429

430 431 432 433
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Get all links connected to this unit
434
                QList<LinkInterface*> links = _linkMgr->getLinks();
435

436 437
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
438
                {
439 440 441
                    // Only forward this message to the other links,
                    // not the link the message was received on
                    if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
442
                }
443
            }
pixhawk's avatar
pixhawk committed
444 445 446 447 448 449 450 451 452 453 454 455
        }
    }
}

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

456
/** @return System id of this application */
457
int MAVLinkProtocol::getSystemId()
458
{
459 460 461 462 463 464
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
465 466 467
}

/** @return Component id of this application */
468
int MAVLinkProtocol::getComponentId()
469
{
470
    return QGC::defaultComponentId;
471 472
}

pixhawk's avatar
pixhawk committed
473 474 475 476 477 478
/**
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
{
    // Get all links connected to this unit
479
    QList<LinkInterface*> links = _linkMgr->getLinks();
pixhawk's avatar
pixhawk committed
480 481 482

    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
483 484
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
485
        sendMessage(*i, message);
486
//        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
487 488 489 490 491 492 493 494 495 496
    }
}

/**
 * @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
497
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
498
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
499 500
    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
501
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
502
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
503
    // If link is connected
504 505
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
506 507 508 509 510
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533
/**
 * @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
534 535 536 537 538 539 540
/**
 * 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()
{
541
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
542
    {
pixhawk's avatar
pixhawk committed
543
        mavlink_message_t beat;
lm's avatar
lm committed
544
        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
545 546
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
547 548
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
549 550
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
551
        memset(&auth, 0, sizeof(auth));
552
        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
553 554 555
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
556 557
}

558
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
559 560
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
561
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
562 563 564
    emit heartbeatChanged(enabled);
}

565 566 567 568 569 570 571 572 573
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

574 575 576 577
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
578
    if (m_authEnabled != enable) {
579 580 581 582 583
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

584 585
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
586
    if (enabled != m_paramGuardEnabled) {
587 588 589 590 591
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

592 593
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
594
    if (enabled != m_actionGuardEnabled) {
595 596 597 598 599
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

600 601
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
602
    if (ms != m_paramRetransmissionTimeout) {
603 604 605 606 607 608 609
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
610
    if (ms != m_paramRewriteTimeout) {
611 612 613 614 615
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

616 617
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
618
    if (ms != m_actionRetransmissionTimeout) {
619 620 621 622 623
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
624 625 626
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
627
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
628 629
}

pixhawk's avatar
pixhawk committed
630 631 632 633 634 635 636
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
637 638
    _heartbeatRate = rate;
    _heartbeatTimer.setInterval(1000/_heartbeatRate);
pixhawk's avatar
pixhawk committed
639 640 641 642 643
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
644
    return _heartbeatRate;
pixhawk's avatar
pixhawk committed
645
}
Don Gagne's avatar
Don Gagne committed
646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670

/// @brief Closes the log file if it is open
bool MAVLinkProtocol::_closeLogFile(void)
{
    if (_tempLogFile.isOpen()) {
        if (_tempLogFile.size() == 0) {
            // Don't save zero byte files
            _tempLogFile.remove();
            return false;
        } else {
            _tempLogFile.flush();
            _tempLogFile.close();
            return true;
        }
    }
    
    return false;
}

void MAVLinkProtocol::_startLogging(void)
{
    Q_ASSERT(!_tempLogFile.isOpen());

    if (!_logSuspendReplay) {
        if (!_tempLogFile.open()) {
671 672
            emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. "
                                                                  "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName()));
Don Gagne's avatar
Don Gagne committed
673 674 675 676 677 678 679 680 681 682 683 684 685 686
            _closeLogFile();
            _logSuspendError = true;
            return;
        }
    
        qDebug() << "Temp log" << _tempLogFile.fileName();
        
        _logSuspendError = false;
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
687
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
688
        if (qgcApp()->promptFlightDataSave()) {
689 690 691 692
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
693 694 695 696 697 698
    }
}

/// @brief Checks the temp directory for log files which may have been left there.
///         This could happen if QGC crashes without the temp log file being saved.
///         Give the user an option to save these orphaned files.
699
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
    
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
    qDebug() << "Orphaned log file count" << fileInfoList.count();
    
    foreach(const QFileInfo fileInfo, fileInfoList) {
        qDebug() << "Orphaned log file" << fileInfo.filePath();
        if (fileInfo.size() == 0) {
            // Delete all zero length files
            QFile::remove(fileInfo.filePath());
            continue;
        }

        // Give the user a chance to save the orphaned log file
        emit protocolStatusMessage(tr("Found unsaved Flight Data"),
                                   tr("This can happen if QGroundControl crashes during Flight Data collection. "
                                      "If you want to save the unsaved Flight Data, select the file you want to save it to. "
                                      "If you do not want to keep the Flight Data, select 'Cancel' on the next dialog."));
        emit saveTempFlightDataLog(fileInfo.filePath());
    }
}

void MAVLinkProtocol::suspendLogForReplay(bool suspend)
{
    _logSuspendReplay = suspend;
}
728 729 730 731 732 733 734 735 736 737 738 739

void MAVLinkProtocol::deleteTempLogFiles(void)
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
    
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
    
    foreach(const QFileInfo fileInfo, fileInfoList) {
        QFile::remove(fileInfo.filePath());
    }
}