MAVLinkProtocol.cc 27 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
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
148 149 150 151 152 153
    int channel = link->getMavlinkChannel();
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
154 155
}

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
{
Don Gagne's avatar
Don Gagne committed
226 227 228 229 230 231 232
    // Since receiveBytes signals cross threads we can end up with signals in the queue
    // that come through after the link is disconnected. For these we just drop the data
    // since the link is closed.
    if (!LinkManager::instance()->containsLink(link)) {
        return;
    }
    
233
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
234 235
    mavlink_message_t message;
    mavlink_status_t status;
236

237
    int mavlinkChannel = link->getMavlinkChannel();
238

239
    static int mavlink09Count = 0;
240
    static int nonmavlinkCount = 0;
241
    static bool decodedFirstPacket = false;
242
    static bool warnedUser = false;
243 244
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
245

246
    for (int position = 0; position < b.size(); position++) {
247
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
248 249

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
250
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
251
        {
252
            warnedUser = true;
253 254
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
255 256 257 258
            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."));
259
        }
pixhawk's avatar
pixhawk committed
260

261 262 263
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
264
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
265
            {
266
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
267 268 269 270 271 272 273 274
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
275 276
                    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."));
277 278 279
                }
            }
        }
280 281
        if (decodeState == 1)
        {
282
            decodedFirstPacket = true;
283 284 285 286 287 288 289 290 291 292 293 294 295 296

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

297 298 299 300 301 302 303 304 305 306
            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
307
            // Log data
Don Gagne's avatar
Don Gagne committed
308
            
Don Gagne's avatar
Don Gagne committed
309
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
310 311 312 313 314 315 316 317 318 319 320 321 322 323 324
                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.
325
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
326
                if(_tempLogFile.write(b) != len)
327
                {
328
                    // If there's an error logging data, raise an alert and stop logging.
329
                    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
330 331
                    _stopLogging();
                    _logSuspendError = true;
332
                }
pixhawk's avatar
pixhawk committed
333 334
            }

pixhawk's avatar
pixhawk committed
335 336 337
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
338

pixhawk's avatar
pixhawk committed
339 340 341
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

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

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

                // Check if the UAS has a different protocol version
368 369
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
370
                    // Bring up dialog to inform user
371 372
                    if (!versionMismatchIgnore)
                    {
373 374 375
                        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));
376 377
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
378 379 380 381 382

                    // Ignore this message and continue gracefully
                    continue;
                }

383 384
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
385

pixhawk's avatar
pixhawk committed
386
            }
387

388
            // Increase receive counter
389 390
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
391

392 393 394 395
            // 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);
396

397 398 399
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
400

401 402
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
403

404 405 406 407 408
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
409

410
                // And log how many were lost for all time and just this timestep
411 412
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
413
            }
414

415 416
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
417

418
            // Update on every 32th packet
419
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
420 421 422
            {
                // Calculate new loss ratio
                // Receive loss
423
                float receiveLoss = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
424
                receiveLoss *= 100.0f;
425 426
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
427 428
                emit receiveLossChanged(message.sysid, receiveLoss);
            }
429

430 431 432 433
            // 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
434

435 436 437 438
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Get all links connected to this unit
439
                QList<LinkInterface*> links = _linkMgr->getLinks();
440

441 442
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
443
                {
444 445 446
                    // 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);
447
                }
448
            }
pixhawk's avatar
pixhawk committed
449 450 451 452 453 454 455 456 457 458 459 460
        }
    }
}

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

461
/** @return System id of this application */
462
int MAVLinkProtocol::getSystemId()
463
{
464 465 466 467 468 469
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
470 471 472
}

/** @return Component id of this application */
473
int MAVLinkProtocol::getComponentId()
474
{
475
    return QGC::defaultComponentId;
476 477
}

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

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

/**
 * @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
502
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
503
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
504
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
505
    mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
506
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
507
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
508
    // If link is connected
509 510
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
511 512 513 514 515
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
516 517 518 519 520 521 522 523 524 525 526 527
/**
 * @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;
528
    mavlink_finalize_message_chan(&message, systemid, componentid, link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
Lorenz Meier's avatar
Lorenz Meier committed
529 530 531 532 533 534 535 536 537 538
    // 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
539 540 541 542 543 544 545
/**
 * 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()
{
546
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
547
    {
pixhawk's avatar
pixhawk committed
548
        mavlink_message_t beat;
lm's avatar
lm committed
549
        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
550 551
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
552 553
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
554 555
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
556
        memset(&auth, 0, sizeof(auth));
557
        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
558 559 560
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
561 562
}

563
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
564 565
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
566
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
567 568 569
    emit heartbeatChanged(enabled);
}

570 571 572 573 574 575 576 577 578
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

579 580 581 582
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
583
    if (m_authEnabled != enable) {
584 585 586 587 588
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

589 590
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
591
    if (enabled != m_paramGuardEnabled) {
592 593 594 595 596
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

597 598
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
599
    if (enabled != m_actionGuardEnabled) {
600 601 602 603 604
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

605 606
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
607
    if (ms != m_paramRetransmissionTimeout) {
608 609 610 611 612 613 614
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
615
    if (ms != m_paramRewriteTimeout) {
616 617 618 619 620
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

621 622
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
623
    if (ms != m_actionRetransmissionTimeout) {
624 625 626 627 628
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
629 630 631
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
632
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
633 634
}

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

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

/// @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()) {
676 677
            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
678 679 680 681 682 683 684 685 686 687 688 689 690 691
            _closeLogFile();
            _logSuspendError = true;
            return;
        }
    
        qDebug() << "Temp log" << _tempLogFile.fileName();
        
        _logSuspendError = false;
    }
}

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

/// @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.
704
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
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
{
    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;
}
733 734 735 736 737 738 739 740 741 742 743 744

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