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

#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASInterface.h"
#include "UAS.h"
#include "LinkManager.h"
26
#include "QGCMAVLink.h"
27
#include "QGC.h"
Don Gagne's avatar
Don Gagne committed
28
#include "QGCApplication.h"
29
#include "QGCLoggingCategory.h"
30
#include "MultiVehicleManager.h"
pixhawk's avatar
pixhawk committed
31

32
Q_DECLARE_METATYPE(mavlink_message_t)
33
IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol)
34
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
35

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

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
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
58 59
    _logSuspendError(false),
    _logSuspendReplay(false),
Don Gagne's avatar
Don Gagne committed
60
    _logWasArmed(false),
61
    _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)),
Don Gagne's avatar
Don Gagne committed
62
#endif
63 64 65
    _linkMgr(LinkManager::instance()),
    _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    _heartbeatsEnabled(true)
pixhawk's avatar
pixhawk committed
66
{
67
    qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
Don Gagne's avatar
Don Gagne committed
68
    
69
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
70
    loadSettings();
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;
        }
    }
83 84 85 86
    
    // 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
87

88 89 90
    connect(this, &MAVLinkProtocol::protocolStatusMessage, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread);
    connect(this, &MAVLinkProtocol::saveTempFlightDataLog, qgcApp(), &QGCApplication::saveTempFlightDataLogOnMainThread);

lm's avatar
lm committed
91
    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
92 93
}

94 95 96 97
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    
Don Gagne's avatar
Don Gagne committed
98
#ifndef __mobile__
99
    _closeLogFile();
Don Gagne's avatar
Don Gagne committed
100
#endif
101 102
}

103 104 105 106 107
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
108
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", _heartbeatsEnabled).toBool());
109 110
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
111 112 113

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
114 115
    if (temp > 0 && temp < 256)
    {
116 117
        systemId = temp;
    }
118

119 120 121 122
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

123 124 125 126 127 128 129
    // 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();
130 131 132 133 134 135 136 137
    settings.endGroup();
}

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

151 152
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
153 154 155 156 157 158
    int channel = link->getMavlinkChannel();
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
159 160
}

161
void MAVLinkProtocol::linkConnected(void)
162 163
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
164
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
165
    
166 167 168 169 170 171 172 173 174 175 176 177 178
    _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)
{
179
    qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected;
180
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
181 182
    
    if (connected) {
183 184 185 186 187 188
        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
189
        
190 191 192 193 194 195 196
#ifndef __mobile__
        if (_connectedLinks.count() == 1) {
            // This is the first link, we need to start logging
            _startLogging();
        }
#endif
        
Don Gagne's avatar
Don Gagne committed
197 198 199
        // Send command to start MAVLink
        // XXX hacky but safe
        // Start NSH
Daniel Agar's avatar
Daniel Agar committed
200
        const char init[] = {0x0d, 0x0d, 0x0d, 0x0d};
Don Gagne's avatar
Don Gagne committed
201 202 203 204 205
        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 {
206 207 208 209 210 211 212 213
        bool found = false;
        for (int i=0; i<_connectedLinks.count(); i++) {
            if (_connectedLinks[i].data() == link) {
                found = true;
                _connectedLinks.removeAt(i);
                break;
            }
        }
214
        Q_UNUSED(found);
215
        Q_ASSERT(found);
Don Gagne's avatar
Don Gagne committed
216
        
Don Gagne's avatar
Don Gagne committed
217
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
218 219 220 221
        if (_connectedLinks.count() == 0) {
            // Last link is gone, close out logging
            _stopLogging();
        }
Don Gagne's avatar
Don Gagne committed
222
#endif
Don Gagne's avatar
Don Gagne committed
223
    }
224 225
}

pixhawk's avatar
pixhawk committed
226 227 228 229 230 231 232
/**
 * 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
 **/
233
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
234
{
Don Gagne's avatar
Don Gagne committed
235 236 237 238 239 240 241
    // 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;
    }
    
242
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
243 244
    mavlink_message_t message;
    mavlink_status_t status;
245

246
    int mavlinkChannel = link->getMavlinkChannel();
247

248
    static int mavlink09Count = 0;
249
    static int nonmavlinkCount = 0;
250
    static bool decodedFirstPacket = false;
251
    static bool warnedUser = false;
252 253
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
254

255
    for (int position = 0; position < b.size(); position++) {
256
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
257 258

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
259
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
260
        {
261
            warnedUser = true;
262 263
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
264 265 266 267
            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."));
268
        }
pixhawk's avatar
pixhawk committed
269

270 271 272
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
273
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
274
            {
275
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
276 277 278 279 280 281 282 283
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
284 285
                    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."));
286 287 288
                }
            }
        }
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);
            }

Don Gagne's avatar
Don Gagne committed
316
#ifndef __mobile__
pixhawk's avatar
pixhawk committed
317
            // Log data
Don Gagne's avatar
Don Gagne committed
318
            
Don Gagne's avatar
Don Gagne committed
319
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
320 321 322 323 324 325 326 327 328 329 330 331 332 333 334
                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.
335
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
336
                if(_tempLogFile.write(b) != len)
337
                {
338
                    // If there's an error logging data, raise an alert and stop logging.
339
                    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
340 341
                    _stopLogging();
                    _logSuspendError = true;
342
                }
Don Gagne's avatar
Don Gagne committed
343 344 345 346 347 348 349 350 351
                
                // Check for the vehicle arming going by. This is used to trigger log save.
                if (!_logWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
                    mavlink_heartbeat_t state;
                    mavlink_msg_heartbeat_decode(&message, &state);
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
                        _logWasArmed = true;
                    }
                }
pixhawk's avatar
pixhawk committed
352
            }
Don Gagne's avatar
Don Gagne committed
353
#endif
pixhawk's avatar
pixhawk committed
354

355 356
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
                // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
357 358
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
359
                if (!MultiVehicleManager::instance()->notifyHeartbeatInfo(link, message.sysid, heartbeat)) {
pixhawk's avatar
pixhawk committed
360 361
                    continue;
                }
pixhawk's avatar
pixhawk committed
362
            }
363

364
            // Increase receive counter
365 366
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
367

368 369 370 371
            // 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);
372

373 374 375
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
376

377 378
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
379

380 381 382 383 384
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
385

386
                // And log how many were lost for all time and just this timestep
387 388
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
389
            }
390

391 392
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
393

394
            // Update on every 32th packet
395
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
396 397 398
            {
                // Calculate new loss ratio
                // Receive loss
399
                float receiveLoss = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
400
                receiveLoss *= 100.0f;
401 402
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
403 404
                emit receiveLossChanged(message.sysid, receiveLoss);
            }
405

406 407 408 409
            // 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
410

411 412 413 414
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Get all links connected to this unit
415
                QList<LinkInterface*> links = _linkMgr->getLinks();
416

417 418
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
419
                {
420 421 422
                    // 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);
423
                }
424
            }
pixhawk's avatar
pixhawk committed
425 426 427 428 429 430 431 432 433 434 435 436
        }
    }
}

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

437
/** @return System id of this application */
438
int MAVLinkProtocol::getSystemId()
439
{
440 441 442 443 444 445
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
446 447 448
}

/** @return Component id of this application */
449
int MAVLinkProtocol::getComponentId()
450
{
451
    return QGC::defaultComponentId;
452 453
}

pixhawk's avatar
pixhawk committed
454 455 456 457 458 459
/**
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
{
    // Get all links connected to this unit
460
    QList<LinkInterface*> links = _linkMgr->getLinks();
pixhawk's avatar
pixhawk committed
461 462 463

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

/**
 * @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
478
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
479
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
480
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
481
    mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
482
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
483
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
484
    // If link is connected
485 486
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
487 488 489 490 491
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
492 493 494 495 496 497 498 499 500 501 502 503
/**
 * @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;
504
    mavlink_finalize_message_chan(&message, systemid, componentid, link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
Lorenz Meier's avatar
Lorenz Meier committed
505 506 507 508 509 510 511 512 513 514
    // 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
515 516 517 518 519 520 521
/**
 * 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()
{
522
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
523
    {
pixhawk's avatar
pixhawk committed
524
        mavlink_message_t beat;
lm's avatar
lm committed
525
        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
526 527
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
528 529
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
530 531
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
532
        memset(&auth, 0, sizeof(auth));
533
        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
534 535 536
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
537 538
}

539
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
540 541
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
542
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
543 544 545
    emit heartbeatChanged(enabled);
}

546 547 548 549 550 551 552 553 554
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

555 556 557 558
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
559
    if (m_authEnabled != enable) {
560 561 562 563 564
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

565 566
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
567
    if (enabled != m_paramGuardEnabled) {
568 569 570 571 572
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

573 574
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
575
    if (enabled != m_actionGuardEnabled) {
576 577 578 579 580
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

581 582
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
583
    if (ms != m_paramRetransmissionTimeout) {
584 585 586 587 588 589 590
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
591
    if (ms != m_paramRewriteTimeout) {
592 593 594 595 596
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

597 598
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
599
    if (ms != m_actionRetransmissionTimeout) {
600 601 602 603 604
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
605 606 607
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
608
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
609 610
}

pixhawk's avatar
pixhawk committed
611 612 613 614 615 616 617
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
618 619
    _heartbeatRate = rate;
    _heartbeatTimer.setInterval(1000/_heartbeatRate);
pixhawk's avatar
pixhawk committed
620 621 622 623 624
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
625
    return _heartbeatRate;
pixhawk's avatar
pixhawk committed
626
}
Don Gagne's avatar
Don Gagne committed
627

Don Gagne's avatar
Don Gagne committed
628
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648
/// @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)
{
649 650 651 652 653 654 655 656 657
    Q_ASSERT(!_tempLogFile.isOpen());

    if (!_logSuspendReplay) {
        if (!_tempLogFile.open()) {
            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()));
            _closeLogFile();
            _logSuspendError = true;
            return;
Don Gagne's avatar
Don Gagne committed
658
        }
659 660 661 662
    
        qDebug() << "Temp log" << _tempLogFile.fileName();
        
        _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
663 664 665 666 667 668
    }
}

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

/// @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.
682
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
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
{
    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;
}
711 712 713 714 715 716 717 718 719 720 721 722

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());
    }
}
Don Gagne's avatar
Don Gagne committed
723
#endif