MAVLinkProtocol.cc 26.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>
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"
pixhawk's avatar
pixhawk committed
32

33
Q_DECLARE_METATYPE(mavlink_message_t)
34

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

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

pixhawk's avatar
pixhawk committed
62
{
63
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
Don Gagne's avatar
Don Gagne committed
64 65 66
    
    _tempLogFile.setFileTemplate(QString("%1/%2.%3").arg(QStandardPaths::writableLocation(QStandardPaths::TempLocation)).arg(_tempLogFileTemplate).arg(_logFileExtension));
    _tempLogFile.setAutoRemove(false);
67

68
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
69
    loadSettings();
Lorenz Meier's avatar
Lorenz Meier committed
70
    moveToThread(this);
71 72 73 74 75

    // 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.
76 77 78 79
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
80 81 82
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
83

Lorenz Meier's avatar
Lorenz Meier committed
84 85
    start(QThread::HighPriority);

lm's avatar
lm committed
86
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
87 88
}

89 90 91 92 93 94
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.sync();
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
95
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool());
96 97
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
98 99 100

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

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

110 111 112 113 114 115 116
    // 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();
117 118 119 120 121 122 123 124 125
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
    settings.setValue("HEARTBEATS_ENABLED", m_heartbeatsEnabled);
126 127
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
128
    settings.setValue("GCS_SYSTEM_ID", systemId);
129 130
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
131 132 133 134
    // 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);
135 136 137 138 139
    settings.endGroup();
    settings.sync();
    //qDebug() << "Storing settings!";
}

pixhawk's avatar
pixhawk committed
140 141
MAVLinkProtocol::~MAVLinkProtocol()
{
142
    storeSettings();
Don Gagne's avatar
Don Gagne committed
143 144
    
    _closeLogFile();
Lorenz Meier's avatar
Lorenz Meier committed
145 146

    // Tell the thread to exit
147
    _should_exit = true;
Lorenz Meier's avatar
Lorenz Meier committed
148 149 150 151 152 153 154 155 156 157
    // Wait for it to exit
    wait();
}

/**
 * @brief Runs the thread
 *
 **/
void MAVLinkProtocol::run()
{
158 159 160 161 162 163 164 165 166
    heartbeatTimer = new QTimer();
    heartbeatTimer->moveToThread(this);
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);

    while(!_should_exit) {

        if (isFinished()) {
167
            delete heartbeatTimer;
168 169 170 171 172 173 174
            qDebug() << "MAVLINK WORKER DONE!";
            return;
        }

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

177 178 179 180 181 182 183 184 185 186
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;
}

187 188 189
void MAVLinkProtocol::linkStatusChanged(bool connected)
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
Don Gagne's avatar
Don Gagne committed
190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227
    
    if (link == NULL) {
        Q_ASSERT(false);
        return;
    }
    
    if (connected) {
        Q_ASSERT(!_connectedLinks.contains(link));
        _connectedLinks.append(link);
        
        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 {
        Q_ASSERT(_connectedLinks.contains(link));
        _connectedLinks.removeOne(link);
        
        if (_connectedLinks.count() == 0) {
            // Last link is gone, close out logging
            _stopLogging();
        }
    }
    
    // Track the links which are connected to the protocol
    QList<LinkInterface*> _connectedLinks;  ///< List of all links connected to protocol

    qDebug() << "linkStatusChanged" << connected;
    
228 229 230 231 232 233 234

    if (link) {
        if (connected) {
        }
    }
}

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

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

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

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

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
263
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
264
        {
265
            warnedUser = true;
266 267
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
268
            emit protocolStatusMessage("MAVLink Version or Baud Rate Mismatch", "Your MAVLink device seems to use the deprecated version 0.9, while QGroundControl only supports version 1.0+. Please upgrade the MAVLink version of your autopilot. If your autopilot is using version 1.0, check if the baud rates of QGroundControl and your autopilot are the same.");
269
        }
pixhawk's avatar
pixhawk committed
270

271 272 273
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
274
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
275
            {
276
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
277 278 279 280 281 282 283 284 285 286 287 288
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
                    emit protocolStatusMessage("MAVLink Baud Rate Mismatch", "Please check if the baud rates of QGroundControl and your autopilot are the same.");
                }
            }
        }
289 290
        if (decodeState == 1)
        {
291
            decodedFirstPacket = true;
292 293 294 295 296 297 298 299 300 301 302 303 304 305

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

306 307 308 309 310 311 312 313 314 315
            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
316
            // Log data
Don Gagne's avatar
Don Gagne committed
317 318 319 320
            
            Q_ASSERT(_logSuspendError || _logSuspendReplay || _tempLogFile.isOpen());
            
            if (!_logSuspendError && !_logSuspendReplay) {
321 322 323 324 325 326 327 328 329 330 331 332 333 334 335
                uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)];

                // Write the uint64 time in microseconds in big endian format before the message.
                // This timestamp is saved in UTC time. We are only saving in ms precision because
                // getting more than this isn't possible with Qt without a ton of extra code.
                quint64 time = (quint64)QDateTime::currentMSecsSinceEpoch() * 1000;
                qToBigEndian(time, buf);

                // Then write the message to the buffer
                int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &message);

                // Determine how many bytes were written by adding the timestamp size to the message size
                len += sizeof(quint64);

                // Now write this timestamp/message pair to the log.
336
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
337
                if(_tempLogFile.write(b) != len)
338
                {
339
                    // If there's an error logging data, raise an alert and stop logging.
Don Gagne's avatar
Don Gagne committed
340 341 342
                    emit protocolStatusMessage(tr("MAVLink Logging failed"), tr("Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName()));
                    _stopLogging();
                    _logSuspendError = true;
343
                }
pixhawk's avatar
pixhawk committed
344 345
            }

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

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

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

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

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

                    // Ignore this message and continue gracefully
                    continue;
                }

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

pixhawk's avatar
pixhawk committed
396
            }
397

398 399 400
            // Increase receive counter
            totalReceiveCounter[linkId]++;
            currReceiveCounter[linkId]++;
401

402 403 404 405
            // 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);
406

407 408 409
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
410

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

414 415 416 417 418
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
419

420 421 422 423
                // And log how many were lost for all time and just this timestep
                totalLossCounter[linkId] += lostMessages;
                currLossCounter[linkId] += lostMessages;
            }
424

425 426
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
427

428 429 430 431 432 433 434 435 436 437 438
            // 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);
            }
439

440 441 442 443
            // 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
444

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

451 452
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
453
                {
454 455 456
                    // 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);
457
                }
458
            }
pixhawk's avatar
pixhawk committed
459 460 461 462 463 464 465 466 467 468 469 470
        }
    }
}

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

471
/** @return System id of this application */
472
int MAVLinkProtocol::getSystemId()
473
{
474 475 476 477 478 479
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
480 481 482
}

/** @return Component id of this application */
483
int MAVLinkProtocol::getComponentId()
484
{
485
    return QGC::defaultComponentId;
486 487
}

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

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

Lorenz Meier's avatar
Lorenz Meier committed
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548
/**
 * @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
549 550 551 552 553 554 555
/**
 * The heartbeat is sent out of order and does not reset the
 * periodic heartbeat emission. It will be just sent in addition.
 * @return mavlink_message_t heartbeat message sent on serial link
 */
void MAVLinkProtocol::sendHeartbeat()
{
Lorenz Meier's avatar
Lorenz Meier committed
556 557
    if (m_heartbeatsEnabled)
    {
pixhawk's avatar
pixhawk committed
558
        mavlink_message_t beat;
lm's avatar
lm committed
559
        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
560 561
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
562 563
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
564 565
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
566
        memset(&auth, 0, sizeof(auth));
567
        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
568 569 570
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
571 572 573 574 575 576 577 578 579
}

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

580 581 582 583 584 585 586 587 588
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

589 590 591 592
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
593
    if (m_authEnabled != enable) {
594 595 596 597 598
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

599 600
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
601
    if (enabled != m_paramGuardEnabled) {
602 603 604 605 606
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

607 608
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
609
    if (enabled != m_actionGuardEnabled) {
610 611 612 613 614
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

615 616
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
617
    if (ms != m_paramRetransmissionTimeout) {
618 619 620 621 622 623 624
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
625
    if (ms != m_paramRewriteTimeout) {
626 627 628 629 630
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

631 632
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
633
    if (ms != m_actionRetransmissionTimeout) {
634 635 636 637 638
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
639 640 641
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
642
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
643 644
}

pixhawk's avatar
pixhawk committed
645 646 647 648 649 650 651 652
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
    heartbeatRate = rate;
653
    heartbeatTimer->setInterval(1000/heartbeatRate);
pixhawk's avatar
pixhawk committed
654 655 656 657 658 659 660
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
    return heartbeatRate;
}
Don Gagne's avatar
Don Gagne committed
661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 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 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760

/// @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()) {
            emit protocolStatusMessage(tr("Opening Flight Data file for writing failed"),
                                       tr("Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName()));
            _closeLogFile();
            _logSuspendError = true;
            return;
        }
    
        qDebug() << "Temp log" << _tempLogFile.fileName();
        
        _logSuspendError = false;
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
        emit saveTempFlightDataLog(_tempLogFile.fileName());
    }
}

/// @brief We override this virtual from QObject so that we can track when the
///         protocolStatusMessage and saveTempFlightDataLog signals are connected.
///         Once both are connected we can check for lost log files.
void MAVLinkProtocol::connectNotify(const QMetaMethod& signal)
{
    if (signal == QMetaMethod::fromSignal(&MAVLinkProtocol::protocolStatusMessage)) {
        _protocolStatusMessageConnected = true;
        if (_saveTempFlightDataLogConnected) {
            _checkLostLogFiles();
        }
    } else if (signal == QMetaMethod::fromSignal(&MAVLinkProtocol::saveTempFlightDataLog)) {
        _saveTempFlightDataLogConnected = true;
        if (_protocolStatusMessageConnected) {
            _checkLostLogFiles();
        }
    }
}

/// @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.
void MAVLinkProtocol::_checkLostLogFiles(void)
{
    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)
{
    // This must come through a slot so that we handle this on the right thread. This will
    // also cause the signal to be queued behind any bytesReady signals which must be flushed
    // out of the queue before we change suspend state.
    Q_ASSERT(QThread::currentThread() == this);
    
    _logSuspendReplay = suspend;
}