MAVLinkProtocol.cc 24.9 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 65 66
    , _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE)
    , _heartbeatsEnabled(true)
    , _linkMgr(NULL)
    , _multiVehicleManager(NULL)
pixhawk's avatar
pixhawk committed
67
{
68

pixhawk's avatar
pixhawk committed
69 70
}

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

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 107 108
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;
       }
   }

   // Start heartbeat timer, emitting a heartbeat at the configured rate
   connect(&_heartbeatTimer, &QTimer::timeout, this, &MAVLinkProtocol::sendHeartbeat);
   _heartbeatTimer.start(1000/_heartbeatRate);

   connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread);
109
#ifndef __mobile__
110
   connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);
111
#endif
112

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

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
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", _heartbeatsEnabled).toBool());
124 125
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
126 127 128

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

134 135 136 137
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

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

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

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

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

196
    int mavlinkChannel = link->getMavlinkChannel();
197

198
    static int mavlink09Count = 0;
199
    static int nonmavlinkCount = 0;
200
    static bool decodedFirstPacket = false;
201
    static bool warnedUser = false;
202 203
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
204

205
    for (int position = 0; position < b.size(); position++) {
206
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
207 208

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

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

            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
252
                    _sendMessage(msg);
253 254 255
                }
            }

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

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

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

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

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

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

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

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

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

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

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

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

363
            // Update on every 32th packet
364
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
365 366 367
            {
                // Calculate new loss ratio
                // Receive loss
368
                float receiveLoss = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
369
                receiveLoss *= 100.0f;
370 371
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
372 373
                emit receiveLossChanged(message.sysid, receiveLoss);
            }
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 449 450 451 452
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

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 472 473 474 475
    // 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
476 477 478 479 480 481 482
/**
 * 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()
{
483
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
484
    {
pixhawk's avatar
pixhawk committed
485
        mavlink_message_t beat;
lm's avatar
lm committed
486
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
Don Gagne's avatar
Don Gagne committed
487
        _sendMessage(beat);
pixhawk's avatar
pixhawk committed
488
    }
Lorenz Meier's avatar
Lorenz Meier committed
489 490
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
491 492
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
493
        memset(&auth, 0, sizeof(auth));
494
        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
495
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
Don Gagne's avatar
Don Gagne committed
496
        _sendMessage(msg);
James Goppert's avatar
James Goppert committed
497
    }
pixhawk's avatar
pixhawk committed
498 499
}

500
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
501 502
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
503
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
504 505 506
    emit heartbeatChanged(enabled);
}

507 508 509 510 511 512 513 514 515
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

516 517 518 519
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
520
    if (m_authEnabled != enable) {
521 522 523 524 525
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

526 527
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
528
    if (enabled != m_paramGuardEnabled) {
529 530 531 532 533
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

534 535
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
536
    if (enabled != m_actionGuardEnabled) {
537 538 539 540 541
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

542 543
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
544
    if (ms != m_paramRetransmissionTimeout) {
545 546 547 548 549 550 551
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
552
    if (ms != m_paramRewriteTimeout) {
553 554 555 556 557
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

558 559
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
560
    if (ms != m_actionRetransmissionTimeout) {
561 562 563 564 565
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
566 567 568
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
569
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
570 571
}

pixhawk's avatar
pixhawk committed
572 573 574 575 576 577 578
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
579 580
    _heartbeatRate = rate;
    _heartbeatTimer.setInterval(1000/_heartbeatRate);
pixhawk's avatar
pixhawk committed
581 582 583 584 585
}

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

Don Gagne's avatar
Don Gagne committed
589 590 591 592 593 594 595 596 597 598 599 600
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
601
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621
/// @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
622 623 624 625 626 627 628 629 630 631
    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;
            }

632 633 634 635 636
            if (_app->promptFlightDataSaveNotArmed()) {
                _logPromptForSave = true;
            }

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

Don Gagne's avatar
Don Gagne committed
638
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
639 640 641 642 643 644 645
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
646
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
647
        if (_logPromptForSave && _app->promptFlightDataSave()) {
648 649 650 651
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
652
    }
653
    _logPromptForSave = false;
Don Gagne's avatar
Don Gagne committed
654 655 656 657 658
}

/// @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.
659
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687
{
    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;
}
688 689 690 691 692 693 694 695 696 697 698 699

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