MAVLinkProtocol.cc 22.9 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * 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

/**
 * @file
pixhawk's avatar
pixhawk committed
13 14
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
15 16 17 18 19 20 21
 */

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

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
22
#include <QApplication>
23
#include <QSettings>
24
#include <QStandardPaths>
25
#include <QtEndian>
26
#include <QMetaType>
pixhawk's avatar
pixhawk committed
27 28 29 30 31 32

#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASInterface.h"
#include "UAS.h"
#include "LinkManager.h"
33
#include "QGCMAVLink.h"
34
#include "QGC.h"
Don Gagne's avatar
Don Gagne committed
35
#include "QGCApplication.h"
36
#include "QGCLoggingCategory.h"
37
#include "MultiVehicleManager.h"
Don Gagne's avatar
Don Gagne committed
38
#include "QGroundControlQmlGlobal.h"
pixhawk's avatar
pixhawk committed
39

40
Q_DECLARE_METATYPE(mavlink_message_t)
41

42
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
43

Don Gagne's avatar
Don Gagne committed
44
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
45 46
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
47
#endif
Don Gagne's avatar
Don Gagne committed
48

pixhawk's avatar
pixhawk committed
49 50 51 52
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
53 54 55 56 57 58 59 60 61 62 63
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
    : QGCTool(app)
    , 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)
64
    , systemId(255)
Don Gagne's avatar
Don Gagne committed
65
#ifndef __mobile__
66 67
    , _logSuspendError(false)
    , _logSuspendReplay(false)
68
    , _logPromptForSave(false)
69
    , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
Don Gagne's avatar
Don Gagne committed
70
#endif
71 72
    , _linkMgr(NULL)
    , _multiVehicleManager(NULL)
pixhawk's avatar
pixhawk committed
73
{
74 75 76 77 78
    memset(&totalReceiveCounter, 0, sizeof(totalReceiveCounter));
    memset(&totalLossCounter, 0, sizeof(totalLossCounter));
    memset(&totalErrorCounter, 0, sizeof(totalErrorCounter));
    memset(&currReceiveCounter, 0, sizeof(currReceiveCounter));
    memset(&currLossCounter, 0, sizeof(currLossCounter));
pixhawk's avatar
pixhawk committed
79 80
}

81 82 83 84
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    
Don Gagne's avatar
Don Gagne committed
85
#ifndef __mobile__
86
    _closeLogFile();
Don Gagne's avatar
Don Gagne committed
87
#endif
88 89
}

90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114
void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);

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

   qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

   m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
   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().

   // Initialize the list for tracking dropped messages to invalid.
   for (int i = 0; i < 256; i++)
   {
       for (int j = 0; j < 256; j++)
       {
           lastIndex[i][j] = -1;
       }
   }

   connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread);
115
#ifndef __mobile__
116
   connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);
117
#endif
118

119 120
   connect(_multiVehicleManager->vehicles(), &QmlObjectListModel::countChanged, this, &MAVLinkProtocol::_vehicleCountChanged);

121 122 123
   emit versionCheckChanged(m_enable_version_check);
}

124 125 126 127 128
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
129 130
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
131 132 133

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

139 140 141 142
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

143 144 145 146 147 148 149
    // 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();
150 151 152 153 154 155 156 157
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
158 159
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
160
    settings.setValue("GCS_SYSTEM_ID", systemId);
161 162
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
163 164 165 166
    // 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);
167 168 169
    settings.endGroup();
}

170 171
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
172 173 174 175 176 177
    int channel = link->getMavlinkChannel();
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
178 179
}

pixhawk's avatar
pixhawk committed
180 181 182 183 184 185 186
/**
 * 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
 **/
187
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
188
{
Don Gagne's avatar
Don Gagne committed
189 190 191
    // 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.
Don Gagne's avatar
Don Gagne committed
192
    if (!_linkMgr->links()->contains(link)) {
Don Gagne's avatar
Don Gagne committed
193 194 195
        return;
    }
    
196
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
197 198
    mavlink_message_t message;
    mavlink_status_t status;
199

200
    int mavlinkChannel = link->getMavlinkChannel();
201

202
    static int mavlink09Count = 0;
203
    static int nonmavlinkCount = 0;
204
    static bool decodedFirstPacket = false;
205
    static bool warnedUser = false;
206 207
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
208

209
    for (int position = 0; position < b.size(); position++) {
210
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
211 212

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
213
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
214
        {
215
            warnedUser = true;
216 217
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
218 219 220 221
            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."));
222
        }
pixhawk's avatar
pixhawk committed
223

224 225 226
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
227
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
228
            {
229
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
230 231 232 233 234 235 236 237
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
238 239
                    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."));
240 241 242
                }
            }
        }
243 244
        if (decodeState == 1)
        {
245
            decodedFirstPacket = true;
246 247 248 249 250 251 252 253 254 255

            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);
256
                    sendMessage(link, msg);
257 258 259
                }
            }

260 261 262 263 264
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);
265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280
                int rssi = rstatus.rssi,
                    remrssi = rstatus.remrssi;
                // 3DR Si1k radio needs rssi fields to be converted to dBm
                if (message.sysid == '3' && message.compid == 'D') {
                    /* Per the Si1K datasheet figure 23.25 and SI AN474 code
                     * samples the relationship between the RSSI register
                     * and received power is as follows:
                     *
                     *                       10
                     * inputPower = rssi * ------ 127
                     *                       19
                     *
                     * Additionally limit to the only realistic range [-120,0] dBm
                     */
                    rssi    = qMin(qMax(qRound(static_cast<qreal>(rssi)    / 1.9 - 127.0), - 120), 0);
                    remrssi = qMin(qMax(qRound(static_cast<qreal>(remrssi) / 1.9 - 127.0), - 120), 0);
281 282 283
                } else {
                    rssi = (int8_t) rstatus.rssi;
                    remrssi = (int8_t) rstatus.remrssi;
284
                }
285

286
                emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rssi, remrssi,
287 288 289
                    rstatus.txbuf, rstatus.noise, rstatus.remnoise);
            }

Don Gagne's avatar
Don Gagne committed
290
#ifndef __mobile__
pixhawk's avatar
pixhawk committed
291
            // Log data
Don Gagne's avatar
Don Gagne committed
292
            
Don Gagne's avatar
Don Gagne committed
293
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
294 295 296 297 298 299 300 301 302 303 304 305 306 307 308
                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.
309
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
310
                if(_tempLogFile.write(b) != len)
311
                {
312
                    // If there's an error logging data, raise an alert and stop logging.
313
                    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
314 315
                    _stopLogging();
                    _logSuspendError = true;
316
                }
Don Gagne's avatar
Don Gagne committed
317 318
                
                // Check for the vehicle arming going by. This is used to trigger log save.
319
                if (!_logPromptForSave && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
320 321 322
                    mavlink_heartbeat_t state;
                    mavlink_msg_heartbeat_decode(&message, &state);
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
323
                        _logPromptForSave = true;
Don Gagne's avatar
Don Gagne committed
324 325
                    }
                }
pixhawk's avatar
pixhawk committed
326
            }
Don Gagne's avatar
Don Gagne committed
327
#endif
pixhawk's avatar
pixhawk committed
328

329
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
330 331 332 333 334
#ifndef __mobile__
                // Start loggin on first heartbeat
                _startLogging();
#endif

335 336
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
Don Gagne's avatar
Don Gagne committed
337
                emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
pixhawk's avatar
pixhawk committed
338
            }
339

340
            // Increase receive counter
341 342
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
343

344 345 346 347
            // 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);
348

349 350 351
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
352

353 354
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
355

356 357 358 359 360
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
361

362
                // And log how many were lost for all time and just this timestep
363 364
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
365
            }
366

367 368
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
369

370
            // Update on every 32th packet
371
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
372 373 374
            {
                // Calculate new loss ratio
                // Receive loss
375 376
                float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
                receiveLossPercent *= 100.0f;
377 378
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
379 380
                emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
                emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
381
            }
382

383 384 385 386
            // 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
387

388 389 390 391
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Emit message on all links that are currently connected
Don Gagne's avatar
Don Gagne committed
392 393 394
                for (int i=0; i<_linkMgr->links()->count(); i++) {
                    LinkInterface* currLink = _linkMgr->links()->value<LinkInterface*>(i);

395 396
                    // Only forward this message to the other links,
                    // not the link the message was received on
397
                    if (currLink && currLink != link) sendMessage(currLink, message);
398
                }
399
            }
pixhawk's avatar
pixhawk committed
400 401 402 403 404 405 406 407 408 409 410 411
        }
    }
}

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

412
/** @return System id of this application */
413
int MAVLinkProtocol::getSystemId()
414
{
415 416 417 418 419 420
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
421 422 423
}

/** @return Component id of this application */
424
int MAVLinkProtocol::getComponentId()
425
{
426
    return 0;
427 428
}

429
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
430
{
Don Gagne's avatar
Don Gagne committed
431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447
    mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->getMavlinkChannel());
    switch (QGroundControlQmlGlobal::mavlinkVersion()->rawValue().toInt()) {
    case QGroundControlQmlGlobal::MavlinkVersion2IfVehicle2:
        if (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
            mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            break;
        }
        // Fallthrough to set version 2
    case QGroundControlQmlGlobal::MavlinkVersionAlways2:
        mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        break;
    default:
    case QGroundControlQmlGlobal::MavlinkVersionAlways1:
        mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        break;
    }

Lorenz Meier's avatar
Lorenz Meier committed
448 449 450 451 452 453 454 455
    // Create buffer
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // 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
456
        link->writeBytesSafe((const char*)buffer, len);
Lorenz Meier's avatar
Lorenz Meier committed
457 458 459
    }
}

460 461 462 463 464 465 466 467 468
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

469 470 471 472
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
473
    if (m_authEnabled != enable) {
474 475 476 477 478
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

479 480
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
481
    if (enabled != m_paramGuardEnabled) {
482 483 484 485 486
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

487 488
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
489
    if (enabled != m_actionGuardEnabled) {
490 491 492 493 494
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

495 496
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
497
    if (ms != m_paramRetransmissionTimeout) {
498 499 500 501 502 503 504
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
505
    if (ms != m_paramRewriteTimeout) {
506 507 508 509 510
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

511 512
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
513
    if (ms != m_actionRetransmissionTimeout) {
514 515 516 517 518
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
519 520 521
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
522
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
523 524
}

Don Gagne's avatar
Don Gagne committed
525 526 527 528 529 530 531 532 533 534 535 536
void MAVLinkProtocol::_vehicleCountChanged(int count)
{
#ifndef __mobile__
    if (count == 0) {
        // Last vehicle is gone, close out logging
        _stopLogging();
    }
#else
    Q_UNUSED(count);
#endif
}

Don Gagne's avatar
Don Gagne committed
537
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557
/// @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)
{
Don Gagne's avatar
Don Gagne committed
558 559 560 561 562 563 564 565 566 567
    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;
            }

568 569 570 571 572
            if (_app->promptFlightDataSaveNotArmed()) {
                _logPromptForSave = true;
            }

            qDebug() << "Temp log" << _tempLogFile.fileName() << _logPromptForSave;
573

Don Gagne's avatar
Don Gagne committed
574
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
575 576 577 578 579 580 581
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
582
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
583
        if (_logPromptForSave && _app->promptFlightDataSave()) {
584 585 586 587
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
588
    }
589
    _logPromptForSave = false;
Don Gagne's avatar
Don Gagne committed
590 591 592 593 594
}

/// @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.
595
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623
{
    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;
}
624 625 626 627 628 629 630 631 632 633 634 635

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
636
#endif