MAVLinkProtocol.cc 26.3 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5
======================================================================*/

/**
 * @file
pixhawk's avatar
pixhawk committed
6 7
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
8 9 10 11 12 13 14
 */

#include <inttypes.h>
#include <iostream>

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
15
#include <QApplication>
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 35
IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol)
Q_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
36

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

pixhawk's avatar
pixhawk committed
40 41 42 43
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
44 45
MAVLinkProtocol::MAVLinkProtocol(QObject* parent) :
    QGCSingleton(parent),
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
    _logSuspendError(false),
    _logSuspendReplay(false),
58
    _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)),
59 60 61
    _linkMgr(LinkManager::instance()),
    _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    _heartbeatsEnabled(true)
pixhawk's avatar
pixhawk committed
62
{
63
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
Don Gagne's avatar
Don Gagne committed
64
    
65
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
66
    loadSettings();
67 68 69 70 71

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

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

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

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

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

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

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

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

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

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

155
void MAVLinkProtocol::linkConnected(void)
156 157
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
158
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
159
    
160 161 162 163 164 165 166 167 168 169 170 171 172
    _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)
{
173
    qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected;
174
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201
    
    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();
        }
    }
202 203
}

pixhawk's avatar
pixhawk committed
204 205 206 207 208 209 210
/**
 * 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
 **/
211
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
212
{
213
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
214 215
    mavlink_message_t message;
    mavlink_status_t status;
216

217 218 219
    // Cache the link ID for common use.
    int linkId = link->getId();

220
    static int mavlink09Count = 0;
221
    static int nonmavlinkCount = 0;
222
    static bool decodedFirstPacket = false;
223
    static bool warnedUser = false;
224 225
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
226

227
    // FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
228
    for (int position = 0; position < b.size(); position++) {
229
        unsigned int decodeState = mavlink_parse_char(linkId, (uint8_t)(b[position]), &message, &status);
230 231

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
232
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
233
        {
234
            warnedUser = true;
235 236
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
237 238 239 240
            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."));
241
        }
pixhawk's avatar
pixhawk committed
242

243 244 245
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
246
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
247
            {
248
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
249 250 251 252 253 254 255 256
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
257 258
                    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."));
259 260 261
                }
            }
        }
262 263
        if (decodeState == 1)
        {
264
            decodedFirstPacket = true;
265 266 267 268 269 270 271 272 273 274 275 276 277 278

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

279 280 281 282 283 284 285 286 287 288
            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
289
            // Log data
Don Gagne's avatar
Don Gagne committed
290
            
Don Gagne's avatar
Don Gagne committed
291
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
292 293 294 295 296 297 298 299 300 301 302 303 304 305 306
                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.
307
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
308
                if(_tempLogFile.write(b) != len)
309
                {
310
                    // If there's an error logging data, raise an alert and stop logging.
311
                    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
312 313
                    _stopLogging();
                    _logSuspendError = true;
314
                }
pixhawk's avatar
pixhawk committed
315 316
            }

pixhawk's avatar
pixhawk committed
317 318 319
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
320

pixhawk's avatar
pixhawk committed
321 322 323
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
324 325
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
326 327 328 329 330 331
                // 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
332
                // Check if the UAS has the same id like this system
333 334
                if (message.sysid == getSystemId())
                {
335
                    emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
336 337
                }

338 339 340 341
                // 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
342
                // First create new UAS object
343 344
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
345 346
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
347
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
348 349

                // Check if the UAS has a different protocol version
350 351
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
352
                    // Bring up dialog to inform user
353 354
                    if (!versionMismatchIgnore)
                    {
355 356 357
                        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));
358 359
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
360 361 362 363 364

                    // Ignore this message and continue gracefully
                    continue;
                }

365 366
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
367

pixhawk's avatar
pixhawk committed
368
            }
369

370 371 372
            // Increase receive counter
            totalReceiveCounter[linkId]++;
            currReceiveCounter[linkId]++;
373

374 375 376 377
            // 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);
378

379 380 381
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
382

383 384
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
385

386 387 388 389 390
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
391

392 393 394 395
                // And log how many were lost for all time and just this timestep
                totalLossCounter[linkId] += lostMessages;
                currLossCounter[linkId] += lostMessages;
            }
396

397 398
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
399

400 401 402 403 404 405 406 407 408 409 410
            // 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);
            }
411

412 413 414 415
            // 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
416

417 418 419 420
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Get all links connected to this unit
421
                QList<LinkInterface*> links = _linkMgr->getLinks();
422

423 424
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
425
                {
426 427 428
                    // 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);
429
                }
430
            }
pixhawk's avatar
pixhawk committed
431 432 433 434 435 436 437 438 439 440 441 442
        }
    }
}

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

443
/** @return System id of this application */
444
int MAVLinkProtocol::getSystemId()
445
{
446 447 448 449 450 451
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
452 453 454
}

/** @return Component id of this application */
455
int MAVLinkProtocol::getComponentId()
456
{
457
    return QGC::defaultComponentId;
458 459
}

pixhawk's avatar
pixhawk committed
460 461 462 463 464 465
/**
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
{
    // Get all links connected to this unit
466
    QList<LinkInterface*> links = _linkMgr->getLinks();
pixhawk's avatar
pixhawk committed
467 468 469

    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
470 471
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
472
        sendMessage(*i, message);
473
//        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
474 475 476 477 478 479 480 481 482 483
    }
}

/**
 * @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
484
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
485
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
486 487
    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
488
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
489
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
490
    // If link is connected
491 492
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
493 494 495 496 497
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520
/**
 * @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
521 522 523 524 525 526 527
/**
 * 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()
{
528
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
529
    {
pixhawk's avatar
pixhawk committed
530
        mavlink_message_t beat;
lm's avatar
lm committed
531
        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
532 533
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
534 535
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
536 537
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
538
        memset(&auth, 0, sizeof(auth));
539
        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
540 541 542
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
543 544
}

545
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
546 547
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
548
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
549 550 551
    emit heartbeatChanged(enabled);
}

552 553 554 555 556 557 558 559 560
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

561 562 563 564
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
565
    if (m_authEnabled != enable) {
566 567 568 569 570
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

571 572
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
573
    if (enabled != m_paramGuardEnabled) {
574 575 576 577 578
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

579 580
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
581
    if (enabled != m_actionGuardEnabled) {
582 583 584 585 586
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

587 588
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
589
    if (ms != m_paramRetransmissionTimeout) {
590 591 592 593 594 595 596
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
597
    if (ms != m_paramRewriteTimeout) {
598 599 600 601 602
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

603 604
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
605
    if (ms != m_actionRetransmissionTimeout) {
606 607 608 609 610
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
611 612 613
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
614
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
615 616
}

pixhawk's avatar
pixhawk committed
617 618 619 620 621 622 623
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
624 625
    _heartbeatRate = rate;
    _heartbeatTimer.setInterval(1000/_heartbeatRate);
pixhawk's avatar
pixhawk committed
626 627 628 629 630
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
631
    return _heartbeatRate;
pixhawk's avatar
pixhawk committed
632
}
Don Gagne's avatar
Don Gagne committed
633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657

/// @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()) {
658 659
            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
660 661 662 663 664 665 666 667 668 669 670 671 672 673
            _closeLogFile();
            _logSuspendError = true;
            return;
        }
    
        qDebug() << "Temp log" << _tempLogFile.fileName();
        
        _logSuspendError = false;
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
674
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
675
        if (qgcApp()->promptFlightDataSave()) {
676 677 678 679
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
680 681 682 683 684 685
    }
}

/// @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.
686
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
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
{
    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;
}
715 716 717 718 719 720 721 722 723 724 725 726

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