MAVLinkProtocol.cc 20.1 KB
Newer Older
1 2
/****************************************************************************
 *
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

pixhawk's avatar
pixhawk committed
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>
20 21
#include <QDir>
#include <QFileInfo>
pixhawk's avatar
pixhawk committed
22 23 24 25 26 27

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

35
Q_DECLARE_METATYPE(mavlink_message_t)
36

37
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
38

39 40
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
41

pixhawk's avatar
pixhawk committed
42 43 44 45
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
46 47
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
48
    , m_enable_version_check(true)
49 50
    , _message({})
    , _status({})
51
    , versionMismatchIgnore(false)
52
    , systemId(255)
53
    , _current_version(100)
54
    , _radio_version_mismatch_count(0)
55 56
    , _logSuspendError(false)
    , _logSuspendReplay(false)
57
    , _vehicleWasArmed(false)
58
    , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
59 60
    , _linkMgr(nullptr)
    , _multiVehicleManager(nullptr)
pixhawk's avatar
pixhawk committed
61
{
62 63 64 65
    memset(totalReceiveCounter, 0, sizeof(totalReceiveCounter));
    memset(totalLossCounter,    0, sizeof(totalLossCounter));
    memset(runningLossPercent,  0, sizeof(runningLossPercent));
    memset(firstMessage,        1, sizeof(firstMessage));
66 67
    memset(&_status,            0, sizeof(_status));
    memset(&_message,           0, sizeof(_message));
pixhawk's avatar
pixhawk committed
68 69
}

70 71 72 73 74 75
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    _closeLogFile();
}

76 77
void MAVLinkProtocol::setVersion(unsigned version)
{
78
    QList<SharedLinkInterfacePtr> sharedLinks = _linkMgr->links();
79

80 81
    for (int i = 0; i < sharedLinks.length(); i++) {
        mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(sharedLinks[i].get()->mavlinkChannel());
82 83 84 85 86 87 88 89 90 91 92 93

        // Set flags for version
        if (version < 200) {
            mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        } else {
            mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        }
    }

    _current_version = version;
}

94 95 96 97 98 99 100 101 102 103 104 105 106 107
void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);

   _linkMgr =               _toolbox->linkManager();
   _multiVehicleManager =   _toolbox->multiVehicleManager();

   qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

   loadSettings();

   // 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().

108 109 110
   connect(this, &MAVLinkProtocol::protocolStatusMessage,   _app, &QGCApplication::criticalMessageBoxOnMainThread);
   connect(this, &MAVLinkProtocol::saveTelemetryLog,        _app, &QGCApplication::saveTelemetryLogOnMainThread);
   connect(this, &MAVLinkProtocol::checkTelemetrySavePath,  _app, &QGCApplication::checkTelemetrySavePathOnMainThread);
111

112 113
   connect(_multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkProtocol::_vehicleCountChanged);
   connect(_multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged);
114

115 116 117
   emit versionCheckChanged(m_enable_version_check);
}

118 119 120 121 122
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
123
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
124 125 126

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
127 128
    if (temp > 0 && temp < 256)
    {
129 130 131 132 133 134 135 136 137
        systemId = temp;
    }
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
138
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
139
    settings.setValue("GCS_SYSTEM_ID", systemId);
140
    // Parameter interface settings
141 142
}

143
void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
144
{
145
    int channel = link->mavlinkChannel();
146
    totalReceiveCounter[channel] = 0;
147 148 149 150 151
    totalLossCounter[channel]    = 0;
    runningLossPercent[channel]  = 0.0f;
    for(int i = 0; i < 256; i++) {
        firstMessage[channel][i] =  1;
    }
152
    link->setDecodedFirstMavlinkPacket(false);
153 154
}

155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186
/**
 * This method parses all outcoming bytes and log a MAVLink packet.
 * @param link The interface to read from
 * @see LinkInterface
 **/

void MAVLinkProtocol::logSentBytes(LinkInterface* link, QByteArray b){

    uint8_t bytes_time[sizeof(quint64)];

    Q_UNUSED(link);
    if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {

        quint64 time = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch() * 1000);

        qToBigEndian(time,bytes_time);

        b.insert(0,QByteArray((const char*)bytes_time,sizeof(bytes_time)));

        int len = b.count();

        if(_tempLogFile.write(b) != len)
        {
            // If there's an error logging data, raise an alert and stop logging.
            emit protocolStatusMessage(tr("MAVLink Protocol"), tr("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName()));
            _stopLogging();
            _logSuspendError = true;
        }
    }

}

pixhawk's avatar
pixhawk committed
187 188 189 190 191 192 193
/**
 * 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
 **/
194

195
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
196
{
Don Gagne's avatar
Don Gagne committed
197 198 199
    // 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.
200
    if (!_linkMgr->containsLink(link)) {
Don Gagne's avatar
Don Gagne committed
201 202
        return;
    }
Gus Grubba's avatar
Gus Grubba committed
203

204
    uint8_t mavlinkChannel = link->mavlinkChannel();
205

206
    for (int position = 0; position < b.size(); position++) {
207 208
        if (mavlink_parse_char(mavlinkChannel, static_cast<uint8_t>(b[position]), &_message, &_status)) {
            // Got a valid message
209
            if (!link->decodedFirstMavlinkPacket()) {
210
                link->setDecodedFirstMavlinkPacket(true);
211 212
                mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
                if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
213
                    qDebug() << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
214
                    mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
215 216
                    // Set all links to v2
                    setVersion(200);
217
                }
Don Gagne's avatar
Don Gagne committed
218 219
            }

220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251
            //-----------------------------------------------------------------
            // MAVLink Status
            uint8_t lastSeq = lastIndex[_message.sysid][_message.compid];
            uint8_t expectedSeq = lastSeq + 1;
            // Increase receive counter
            totalReceiveCounter[mavlinkChannel]++;
            // Determine what the next expected sequence number is, accounting for
            // never having seen a message for this system/component pair.
            if(firstMessage[_message.sysid][_message.compid]) {
                firstMessage[_message.sysid][_message.compid] = 0;
                lastSeq     = _message.seq;
                expectedSeq = _message.seq;
            }
            // And if we didn't encounter that sequence number, record the error
            //int foo = 0;
            if (_message.seq != expectedSeq)
            {
                //foo = 1;
                int lostMessages = 0;
                //-- Account for overflow during packet loss
                if(_message.seq < expectedSeq) {
                    lostMessages = (_message.seq + 255) - expectedSeq;
                } else {
                    lostMessages = _message.seq - expectedSeq;
                }
                // Log how many were lost
                totalLossCounter[mavlinkChannel] += static_cast<uint64_t>(lostMessages);
            }

            // And update the last sequence number for this system/component pair
            lastIndex[_message.sysid][_message.compid] = _message.seq;;
            // Calculate new loss ratio
252 253
            uint64_t totalSent = totalReceiveCounter[mavlinkChannel] + totalLossCounter[mavlinkChannel];
            float receiveLossPercent = static_cast<float>(static_cast<double>(totalLossCounter[mavlinkChannel]) / static_cast<double>(totalSent));
254 255 256 257 258 259
            receiveLossPercent *= 100.0f;
            receiveLossPercent = (receiveLossPercent * 0.5f) + (runningLossPercent[mavlinkChannel] * 0.5f);
            runningLossPercent[mavlinkChannel] = receiveLossPercent;

            //qDebug() << foo << _message.seq << expectedSeq << lastSeq << totalLossCounter[mavlinkChannel] << totalReceiveCounter[mavlinkChannel] << totalSentCounter[mavlinkChannel] << "(" << _message.sysid << _message.compid << ")";

260 261 262 263 264 265 266 267 268 269 270 271 272
            //-----------------------------------------------------------------
            // MAVLink forwarding
            bool forwardingEnabled = _app->toolbox()->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool();
            if (forwardingEnabled) {
                SharedLinkInterfacePtr forwardingLink = _linkMgr->mavlinkForwardingLink();

                if (forwardingLink) {
                    uint8_t buf[MAVLINK_MAX_PACKET_LEN];
                    int len = mavlink_msg_to_send_buffer(buf, &_message);
                    forwardingLink->writeBytesThreadSafe((const char*)buf, len);
                }
            }

273
            //-----------------------------------------------------------------
pixhawk's avatar
pixhawk committed
274
            // Log data
Don Gagne's avatar
Don Gagne committed
275
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
276 277 278 279 280
                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.
281
                quint64 time = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch() * 1000);
282 283 284
                qToBigEndian(time, buf);

                // Then write the message to the buffer
285
                int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &_message);
286 287 288 289 290

                // 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.
291
                QByteArray b(reinterpret_cast<const char*>(buf), len);
Don Gagne's avatar
Don Gagne committed
292
                if(_tempLogFile.write(b) != len)
293
                {
294
                    // If there's an error logging data, raise an alert and stop logging.
295
                    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
296 297
                    _stopLogging();
                    _logSuspendError = true;
298
                }
Gus Grubba's avatar
Gus Grubba committed
299

Don Gagne's avatar
Don Gagne committed
300
                // Check for the vehicle arming going by. This is used to trigger log save.
301
                if (!_vehicleWasArmed && _message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
302
                    mavlink_heartbeat_t state;
303
                    mavlink_msg_heartbeat_decode(&_message, &state);
Don Gagne's avatar
Don Gagne committed
304
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
305
                        _vehicleWasArmed = true;
Don Gagne's avatar
Don Gagne committed
306 307
                    }
                }
pixhawk's avatar
pixhawk committed
308 309
            }

310
            if (_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
311
                _startLogging();
312
                mavlink_heartbeat_t heartbeat;
313 314
                mavlink_msg_heartbeat_decode(&_message, &heartbeat);
                emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, heartbeat.autopilot, heartbeat.type);
315 316 317 318 319 320 321
            } else if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY) {
                _startLogging();
                mavlink_high_latency_t highLatency;
                mavlink_msg_high_latency_decode(&_message, &highLatency);
                // HIGH_LATENCY does not provide autopilot or type information, generic is our safest bet
                emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC);
            } else if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) {
322 323
                _startLogging();
                mavlink_high_latency2_t highLatency2;
324 325
                mavlink_msg_high_latency2_decode(&_message, &highLatency2);
                emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, highLatency2.autopilot, highLatency2.type);
pixhawk's avatar
pixhawk committed
326
            }
327

328 329 330 331 332
#if 0
            // Given the current state of SiK Radio firmwares there is no way to make the code below work.
            // The ArduPilot implementation of SiK Radio firmware always sends MAVLINK_MSG_ID_RADIO_STATUS as a mavlink 1
            // packet even if the vehicle is sending Mavlink 2.

333 334
            // Detect if we are talking to an old radio not supporting v2
            mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
Don Gagne's avatar
Don Gagne committed
335
            if (_message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _radio_version_mismatch_count != -1) {
336 337 338 339 340 341 342 343 344
                if ((mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)
                && !(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
                    _radio_version_mismatch_count++;
                }
            }

            if (_radio_version_mismatch_count == 5) {
                // Warn the user if the radio continues to send v1 while the link uses v2
                emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Detected radio still using MAVLink v1.0 on a link with MAVLink v2.0 enabled. Please upgrade the radio firmware."));
Don Gagne's avatar
Don Gagne committed
345 346
                // Set to flag warning already shown
                _radio_version_mismatch_count = -1;
347 348 349 350
                // Flick link back to v1
                qDebug() << "Switching outbound to mavlink 1.0 due to incoming mavlink 1.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
                mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            }
351
#endif
352

353 354
            // Update MAVLink status on every 32th packet
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0) {
355
                emit mavlinkMessageStatus(_message.sysid, totalSent, totalReceiveCounter[mavlinkChannel], totalLossCounter[mavlinkChannel], receiveLossPercent);
356
            }
357

358 359 360
            // 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
361 362 363 364
            emit messageReceived(link, _message);
            // Reset message parsing
            memset(&_status,  0, sizeof(_status));
            memset(&_message, 0, sizeof(_message));
pixhawk's avatar
pixhawk committed
365 366 367 368 369 370 371 372 373
        }
    }
}

/**
 * @return The name of this protocol
 **/
QString MAVLinkProtocol::getName()
{
374
    return tr("MAVLink protocol");
pixhawk's avatar
pixhawk committed
375 376
}

377
/** @return System id of this application */
378
int MAVLinkProtocol::getSystemId()
379
{
380 381 382 383 384 385
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
386 387 388
}

/** @return Component id of this application */
389
int MAVLinkProtocol::getComponentId()
390
{
391
    return MAV_COMP_ID_MISSIONPLANNER;
392 393
}

lm's avatar
lm committed
394 395 396
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
397
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
398 399
}

400
void MAVLinkProtocol::_vehicleCountChanged(void)
Don Gagne's avatar
Don Gagne committed
401
{
402
    int count = _multiVehicleManager->vehicles()->count();
Don Gagne's avatar
Don Gagne committed
403 404 405
    if (count == 0) {
        // Last vehicle is gone, close out logging
        _stopLogging();
406
        _radio_version_mismatch_count = 0;
Don Gagne's avatar
Don Gagne committed
407 408 409
    }
}

Don Gagne's avatar
Don Gagne committed
410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428
/// @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)
{
429
    //-- Are we supposed to write logs?
430 431 432
    if (qgcApp()->runningUnitTests()) {
        return;
    }
433 434 435 436
    AppSettings* appSettings = _app->toolbox()->settingsManager()->appSettings();
    if(appSettings->disableAllPersistence()->rawValue().toBool()) {
        return;
    }
437 438
#ifdef __mobile__
    //-- Mobile build don't write to /tmp unless told to do so
439
    if (!appSettings->telemetrySave()->rawValue().toBool()) {
440 441 442 443 444
        return;
    }
#endif
    //-- Log is always written to a temp file. If later the user decides they want
    //   it, it's all there for them.
Don Gagne's avatar
Don Gagne committed
445 446 447 448 449 450 451 452 453 454
    if (!_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;
            }

455
            qDebug() << "Temp log" << _tempLogFile.fileName();
456
            emit checkTelemetrySavePath();
457

Don Gagne's avatar
Don Gagne committed
458
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
459 460 461 462 463 464
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
465 466 467
    if (_tempLogFile.isOpen()) {
        if (_closeLogFile()) {
            if ((_vehicleWasArmed || _app->toolbox()->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) &&
468 469
                _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool() &&
                !_app->toolbox()->settingsManager()->appSettings()->disableAllPersistence()->rawValue().toBool()) {
470 471 472 473
                emit saveTelemetryLog(_tempLogFile.fileName());
            } else {
                QFile::remove(_tempLogFile.fileName());
            }
474
        }
Don Gagne's avatar
Don Gagne committed
475
    }
476
    _vehicleWasArmed = false;
Don Gagne's avatar
Don Gagne committed
477 478 479 480 481
}

/// @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.
482
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
483 484
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
Gus Grubba's avatar
Gus Grubba committed
485

Don Gagne's avatar
Don Gagne committed
486 487
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
488
    //qDebug() << "Orphaned log file count" << fileInfoList.count();
Gus Grubba's avatar
Gus Grubba committed
489

490
    for(const QFileInfo& fileInfo: fileInfoList) {
491
        //qDebug() << "Orphaned log file" << fileInfo.filePath();
Don Gagne's avatar
Don Gagne committed
492 493 494 495 496
        if (fileInfo.size() == 0) {
            // Delete all zero length files
            QFile::remove(fileInfo.filePath());
            continue;
        }
497
        emit saveTelemetryLog(fileInfo.filePath());
Don Gagne's avatar
Don Gagne committed
498 499 500 501 502 503 504
    }
}

void MAVLinkProtocol::suspendLogForReplay(bool suspend)
{
    _logSuspendReplay = suspend;
}
505 506 507 508

void MAVLinkProtocol::deleteTempLogFiles(void)
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
Gus Grubba's avatar
Gus Grubba committed
509

510 511
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
Gus Grubba's avatar
Gus Grubba committed
512

513
    for (const QFileInfo& fileInfo: fileInfoList) {
514 515 516
        QFile::remove(fileInfo.filePath());
    }
}
517