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

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 47 48 49 50 51 52 53 54 55 56
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)
    , systemId(QGC::defaultSystemId)
Don Gagne's avatar
Don Gagne committed
57
#ifndef __mobile__
58 59
    , _logSuspendError(false)
    , _logSuspendReplay(false)
60
    , _logPromptForSave(false)
61
    , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
Don Gagne's avatar
Don Gagne committed
62
#endif
63 64
    , _linkMgr(NULL)
    , _multiVehicleManager(NULL)
pixhawk's avatar
pixhawk committed
65
{
66 67 68 69 70
    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
71 72
}

73 74 75 76
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    
Don Gagne's avatar
Don Gagne committed
77
#ifndef __mobile__
78
    _closeLogFile();
Don Gagne's avatar
Don Gagne committed
79
#endif
80 81
}

82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106
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);
107
#ifndef __mobile__
108
   connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);
109
#endif
110

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

113 114 115
   emit versionCheckChanged(m_enable_version_check);
}

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

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

131 132 133 134
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

135 136 137 138 139 140 141
    // 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();
142 143 144 145 146 147 148 149
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
150 151
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
152
    settings.setValue("GCS_SYSTEM_ID", systemId);
153 154
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
155 156 157 158
    // 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);
159 160 161
    settings.endGroup();
}

162 163
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
164 165 166 167 168 169
    int channel = link->getMavlinkChannel();
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
170 171
}

pixhawk's avatar
pixhawk committed
172 173 174 175 176 177 178
/**
 * 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
 **/
179
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
180
{
Don Gagne's avatar
Don Gagne committed
181 182 183
    // 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
184
    if (!_linkMgr->links()->contains(link)) {
Don Gagne's avatar
Don Gagne committed
185 186 187
        return;
    }
    
188
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
189 190
    mavlink_message_t message;
    mavlink_status_t status;
191

192
    int mavlinkChannel = link->getMavlinkChannel();
193

194
    static int mavlink09Count = 0;
195
    static int nonmavlinkCount = 0;
196
    static bool decodedFirstPacket = false;
197
    static bool warnedUser = false;
198 199
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
200

201
    for (int position = 0; position < b.size(); position++) {
202
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
203 204

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
205
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
206
        {
207
            warnedUser = true;
208 209
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
210 211 212 213
            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."));
214
        }
pixhawk's avatar
pixhawk committed
215

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

            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);
Don Gagne's avatar
Don Gagne committed
248
                    _sendMessage(msg);
249 250 251
                }
            }

252 253 254 255 256
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);
257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
                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);
273 274 275
                } else {
                    rssi = (int8_t) rstatus.rssi;
                    remrssi = (int8_t) rstatus.remrssi;
276
                }
277

278
                emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rssi, remrssi,
279 280 281
                    rstatus.txbuf, rstatus.noise, rstatus.remnoise);
            }

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

321
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
322 323 324 325 326
#ifndef __mobile__
                // Start loggin on first heartbeat
                _startLogging();
#endif

327 328
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
Don Gagne's avatar
Don Gagne committed
329
                emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
pixhawk's avatar
pixhawk committed
330
            }
331

332
            // Increase receive counter
333 334
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
335

336 337 338 339
            // 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);
340

341 342 343
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
344

345 346
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
347

348 349 350 351 352
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
353

354
                // And log how many were lost for all time and just this timestep
355 356
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
357
            }
358

359 360
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
361

362
            // Update on every 32th packet
363
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
364 365 366
            {
                // Calculate new loss ratio
                // Receive loss
367 368
                float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
                receiveLossPercent *= 100.0f;
369 370
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
371 372
                emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
                emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
373
            }
374

375 376 377 378
            // 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
379

380 381 382 383
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Emit message on all links that are currently connected
Don Gagne's avatar
Don Gagne committed
384 385 386
                for (int i=0; i<_linkMgr->links()->count(); i++) {
                    LinkInterface* currLink = _linkMgr->links()->value<LinkInterface*>(i);

387 388
                    // Only forward this message to the other links,
                    // not the link the message was received on
Don Gagne's avatar
Don Gagne committed
389
                    if (currLink && currLink != link) _sendMessage(currLink, message, message.sysid, message.compid);
390
                }
391
            }
pixhawk's avatar
pixhawk committed
392 393 394 395 396 397 398 399 400 401 402 403
        }
    }
}

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

404
/** @return System id of this application */
405
int MAVLinkProtocol::getSystemId()
406
{
407 408 409 410 411 412
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
413 414 415
}

/** @return Component id of this application */
416
int MAVLinkProtocol::getComponentId()
417
{
418
    return QGC::defaultComponentId;
419 420
}

pixhawk's avatar
pixhawk committed
421 422 423
/**
 * @param message message to send
 */
Don Gagne's avatar
Don Gagne committed
424
void MAVLinkProtocol::_sendMessage(mavlink_message_t message)
pixhawk's avatar
pixhawk committed
425
{
Don Gagne's avatar
Don Gagne committed
426 427 428
    for (int i=0; i<_linkMgr->links()->count(); i++) {
        LinkInterface* link = _linkMgr->links()->value<LinkInterface*>(i);
        _sendMessage(link, message);
pixhawk's avatar
pixhawk committed
429 430 431 432 433 434 435
    }
}

/**
 * @param link the link to send the message over
 * @param message message to send
 */
Don Gagne's avatar
Don Gagne committed
436
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message)
pixhawk's avatar
pixhawk committed
437 438
{
    // Create buffer
Lorenz Meier's avatar
Lorenz Meier committed
439
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
440
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
441
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
442
    mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
443
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
444
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
445
    // If link is connected
446 447
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
448
        // Send the portion of the buffer now occupied by the message
449
        link->writeBytesSafe((const char*)buffer, len);
pixhawk's avatar
pixhawk committed
450 451 452
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
453 454 455 456 457 458
/**
 * @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
 */
Don Gagne's avatar
Don Gagne committed
459
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
Lorenz Meier's avatar
Lorenz Meier committed
460 461 462 463 464
{
    // 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;
465
    mavlink_finalize_message_chan(&message, systemid, componentid, link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
Lorenz Meier's avatar
Lorenz Meier committed
466 467 468 469 470 471
    // 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
472
        link->writeBytesSafe((const char*)buffer, len);
Lorenz Meier's avatar
Lorenz Meier committed
473 474 475
    }
}

476 477 478 479 480 481 482 483 484
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

485 486 487 488
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
489
    if (m_authEnabled != enable) {
490 491 492 493 494
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

495 496
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
497
    if (enabled != m_paramGuardEnabled) {
498 499 500 501 502
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

503 504
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
505
    if (enabled != m_actionGuardEnabled) {
506 507 508 509 510
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

511 512
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
513
    if (ms != m_paramRetransmissionTimeout) {
514 515 516 517 518 519 520
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
521
    if (ms != m_paramRewriteTimeout) {
522 523 524 525 526
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

527 528
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
529
    if (ms != m_actionRetransmissionTimeout) {
530 531 532 533 534
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
535 536 537
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
538
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
539 540
}

Don Gagne's avatar
Don Gagne committed
541 542 543 544 545 546 547 548 549 550 551 552
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
553
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573
/// @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
574 575 576 577 578 579 580 581 582 583
    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;
            }

584 585 586 587 588
            if (_app->promptFlightDataSaveNotArmed()) {
                _logPromptForSave = true;
            }

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

Don Gagne's avatar
Don Gagne committed
590
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
591 592 593 594 595 596 597
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
598
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
599
        if (_logPromptForSave && _app->promptFlightDataSave()) {
600 601 602 603
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
604
    }
605
    _logPromptForSave = false;
Don Gagne's avatar
Don Gagne committed
606 607 608 609 610
}

/// @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.
611
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639
{
    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;
}
640 641 642 643 644 645 646 647 648 649 650 651

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