MAVLinkProtocol.cc 25.7 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 60 61
    , _logSuspendError(false)
    , _logSuspendReplay(false)
    , _logWasArmed(false)
    , _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 109 110
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);
   connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);

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
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", _heartbeatsEnabled).toBool());
122 123
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).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
        systemId = temp;
    }
131

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

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

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

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

174
void MAVLinkProtocol::linkConnected(void)
175 176
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
177
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
178
    
179 180 181 182 183 184 185 186 187 188 189 190 191
    _linkStatusChanged(link, true);
}

void MAVLinkProtocol::linkDisconnected(void)
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
    Q_ASSERT(link);
    
    _linkStatusChanged(link, false);
}

void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
{
192
    qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected;
193
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
194 195
    
    if (connected) {
196 197 198 199 200
        foreach (SharedLinkInterface sharedLink, _connectedLinks) {
            Q_ASSERT(sharedLink.data() != link);
        }
        
        // Use the same shared pointer as LinkManager
201
        _connectedLinks.append(_linkMgr->sharedPointerForLink(link));
Don Gagne's avatar
Don Gagne committed
202 203 204 205
        
        // Send command to start MAVLink
        // XXX hacky but safe
        // Start NSH
Daniel Agar's avatar
Daniel Agar committed
206
        const char init[] = {0x0d, 0x0d, 0x0d, 0x0d};
Don Gagne's avatar
Don Gagne committed
207 208 209 210 211
        link->writeBytes(init, sizeof(init));
        const char* cmd = "sh /etc/init.d/rc.usb\n";
        link->writeBytes(cmd, strlen(cmd));
        link->writeBytes(init, 4);
    } else {
212 213 214 215 216 217 218 219
        bool found = false;
        for (int i=0; i<_connectedLinks.count(); i++) {
            if (_connectedLinks[i].data() == link) {
                found = true;
                _connectedLinks.removeAt(i);
                break;
            }
        }
220
        Q_UNUSED(found);
221
        Q_ASSERT(found);
Don Gagne's avatar
Don Gagne committed
222
    }
223 224
}

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

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

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

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

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

269 270 271
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
272
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
273
            {
274
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
275 276 277 278 279 280 281 282
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
283 284
                    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."));
285 286 287
                }
            }
        }
288 289
        if (decodeState == 1)
        {
290
            decodedFirstPacket = true;
291 292 293 294 295 296 297 298 299 300 301 302 303 304

            if(message.msgid == MAVLINK_MSG_ID_PING)
            {
                // process ping requests (tgt_system and tgt_comp must be zero)
                mavlink_ping_t ping;
                mavlink_msg_ping_decode(&message, &ping);
                if(!ping.target_system && !ping.target_component)
                {
                    mavlink_message_t msg;
                    mavlink_msg_ping_pack(getSystemId(), getComponentId(), &msg, ping.time_usec, ping.seq, message.sysid, message.compid);
                    sendMessage(msg);
                }
            }

305 306 307 308 309 310 311 312 313 314
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);

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

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

354
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
355 356 357 358 359
#ifndef __mobile__
                // Start loggin on first heartbeat
                _startLogging();
#endif

360
                // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
361 362
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
363
                if (!_multiVehicleManager->notifyHeartbeatInfo(link, message.sysid, heartbeat)) {
pixhawk's avatar
pixhawk committed
364 365
                    continue;
                }
pixhawk's avatar
pixhawk committed
366
            }
367

368
            // Increase receive counter
369 370
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
371

372 373 374 375
            // 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);
376

377 378 379
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
380

381 382
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
383

384 385 386 387 388
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
389

390
                // And log how many were lost for all time and just this timestep
391 392
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
393
            }
394

395 396
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
397

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

410 411 412 413
            // 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
414

415 416 417 418
            // Multiplex message if enabled
            if (m_multiplexingEnabled)
            {
                // Get all links connected to this unit
419
                QList<LinkInterface*> links = _linkMgr->getLinks();
420

421 422
                // Emit message on all links that are currently connected
                foreach (LinkInterface* currLink, links)
423
                {
424 425 426
                    // Only forward this message to the other links,
                    // not the link the message was received on
                    if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
427
                }
428
            }
pixhawk's avatar
pixhawk committed
429 430 431 432 433 434 435 436 437 438 439 440
        }
    }
}

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

441
/** @return System id of this application */
442
int MAVLinkProtocol::getSystemId()
443
{
444 445 446 447 448 449
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
450 451 452
}

/** @return Component id of this application */
453
int MAVLinkProtocol::getComponentId()
454
{
455
    return QGC::defaultComponentId;
456 457
}

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

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

/**
 * @param link the link to send the message over
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
{
    // Create buffer
Lorenz Meier's avatar
Lorenz Meier committed
482
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
483
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
484
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
485
    mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
486
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
487
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
488
    // If link is connected
489 490
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
491 492 493 494 495
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
496 497 498 499 500 501 502 503 504 505 506 507
/**
 * @param link the link to send the message over
 * @param message message to send
 * @param systemid id of the system the message is originating from
 * @param componentid id of the component the message is originating from
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
{
    // Create buffer
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Rewriting header to ensure correct link ID is set
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
508
    mavlink_finalize_message_chan(&message, systemid, componentid, link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
Lorenz Meier's avatar
Lorenz Meier committed
509 510 511 512 513 514 515 516 517 518
    // 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
519 520 521 522 523 524 525
/**
 * 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()
{
526
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
527
    {
pixhawk's avatar
pixhawk committed
528
        mavlink_message_t beat;
lm's avatar
lm committed
529
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
pixhawk's avatar
pixhawk committed
530 531
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
532 533
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
534 535
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
536
        memset(&auth, 0, sizeof(auth));
537
        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
538 539 540
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
541 542
}

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

550 551 552 553 554 555 556 557 558
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

559 560 561 562
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
563
    if (m_authEnabled != enable) {
564 565 566 567 568
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

569 570
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
571
    if (enabled != m_paramGuardEnabled) {
572 573 574 575 576
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

577 578
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
579
    if (enabled != m_actionGuardEnabled) {
580 581 582 583 584
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

585 586
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
587
    if (ms != m_paramRetransmissionTimeout) {
588 589 590 591 592 593 594
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
595
    if (ms != m_paramRewriteTimeout) {
596 597 598 599 600
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

601 602
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
603
    if (ms != m_actionRetransmissionTimeout) {
604 605 606 607 608
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
609 610 611
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
612
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
613 614
}

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

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

Don Gagne's avatar
Don Gagne committed
632 633 634 635 636 637 638 639 640 641 642 643
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
644
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664
/// @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
665 666 667 668 669 670 671 672 673 674 675
    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;
            }

            qDebug() << "Temp log" << _tempLogFile.fileName();
676

Don Gagne's avatar
Don Gagne committed
677
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
678 679 680 681 682 683 684
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
685
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
686
        if (_logWasArmed && _app->promptFlightDataSave()) {
687 688 689 690
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
691
    }
Don Gagne's avatar
Don Gagne committed
692
    _logWasArmed = false;
Don Gagne's avatar
Don Gagne committed
693 694 695 696 697
}

/// @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.
698
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726
{
    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;
}
727 728 729 730 731 732 733 734 735 736 737 738

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