MAVLinkProtocol.cc 25.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
}

176
void MAVLinkProtocol::linkConnected(void)
177 178
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
179
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
180
    
181 182 183 184 185 186 187 188 189 190 191 192 193
    _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)
{
194
    qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected;
195
    Q_ASSERT(link);
Don Gagne's avatar
Don Gagne committed
196 197
    
    if (connected) {
198 199 200 201 202 203 204 205 206 207
        if (link->requiresUSBMavlinkStart()) {
            // Send command to start MAVLink
            // XXX hacky but safe
            // Start NSH
            const char init[] = {0x0d, 0x0d, 0x0d, 0x0d};
            link->writeBytes(init, sizeof(init));
            const char* cmd = "sh /etc/init.d/rc.usb\n";
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 4);
        }
Don Gagne's avatar
Don Gagne committed
208
    }
209 210
}

pixhawk's avatar
pixhawk committed
211 212 213 214 215 216 217
/**
 * 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
 **/
218
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
219
{
Don Gagne's avatar
Don Gagne committed
220 221 222
    // 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
223
    if (!_linkMgr->links()->contains(link)) {
Don Gagne's avatar
Don Gagne committed
224 225 226
        return;
    }
    
227
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
228 229
    mavlink_message_t message;
    mavlink_status_t status;
230

231
    int mavlinkChannel = link->getMavlinkChannel();
232

233
    static int mavlink09Count = 0;
234
    static int nonmavlinkCount = 0;
235
    static bool decodedFirstPacket = false;
236
    static bool warnedUser = false;
237 238
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
239

240
    for (int position = 0; position < b.size(); position++) {
241
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
242 243

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
244
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
245
        {
246
            warnedUser = true;
247 248
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
249 250 251 252
            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."));
253
        }
pixhawk's avatar
pixhawk committed
254

255 256 257
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
258
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
259
            {
260
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
261 262 263 264 265 266 267 268
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
269 270
                    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."));
271 272 273
                }
            }
        }
274 275
        if (decodeState == 1)
        {
276
            decodedFirstPacket = true;
277 278 279 280 281 282 283 284 285 286

            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
287
                    _sendMessage(msg);
288 289 290
                }
            }

291 292 293 294 295
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);
296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312
                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);
                }
313

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

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

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

363 364
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
Don Gagne's avatar
Don Gagne committed
365
                emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
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)
            {
                // Emit message on all links that are currently connected
Don Gagne's avatar
Don Gagne committed
419 420 421
                for (int i=0; i<_linkMgr->links()->count(); i++) {
                    LinkInterface* currLink = _linkMgr->links()->value<LinkInterface*>(i);

422 423
                    // Only forward this message to the other links,
                    // not the link the message was received on
Don Gagne's avatar
Don Gagne committed
424
                    if (currLink && currLink != link) _sendMessage(currLink, message, message.sysid, message.compid);
425
                }
426
            }
pixhawk's avatar
pixhawk committed
427 428 429 430 431 432 433 434 435 436 437 438
        }
    }
}

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

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

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
448 449 450
}

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

pixhawk's avatar
pixhawk committed
456 457 458
/**
 * @param message message to send
 */
Don Gagne's avatar
Don Gagne committed
459
void MAVLinkProtocol::_sendMessage(mavlink_message_t message)
pixhawk's avatar
pixhawk committed
460
{
Don Gagne's avatar
Don Gagne committed
461 462 463
    for (int i=0; i<_linkMgr->links()->count(); i++) {
        LinkInterface* link = _linkMgr->links()->value<LinkInterface*>(i);
        _sendMessage(link, message);
pixhawk's avatar
pixhawk committed
464 465 466 467 468 469 470
    }
}

/**
 * @param link the link to send the message over
 * @param message message to send
 */
Don Gagne's avatar
Don Gagne committed
471
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message)
pixhawk's avatar
pixhawk committed
472 473
{
    // Create buffer
Lorenz Meier's avatar
Lorenz Meier committed
474
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
475
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
476
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
477
    mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
478
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
479
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
480
    // If link is connected
481 482
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
483 484 485 486 487
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
488 489 490 491 492 493
/**
 * @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
494
void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
Lorenz Meier's avatar
Lorenz Meier committed
495 496 497 498 499
{
    // 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;
500
    mavlink_finalize_message_chan(&message, systemid, componentid, link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);
Lorenz Meier's avatar
Lorenz Meier committed
501 502 503 504 505 506 507 508 509 510
    // 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
511 512 513 514 515 516 517
/**
 * 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()
{
518
    if (_heartbeatsEnabled)
Lorenz Meier's avatar
Lorenz Meier committed
519
    {
pixhawk's avatar
pixhawk committed
520
        mavlink_message_t beat;
lm's avatar
lm committed
521
        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
522
        _sendMessage(beat);
pixhawk's avatar
pixhawk committed
523
    }
Lorenz Meier's avatar
Lorenz Meier committed
524 525
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
526 527
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
528
        memset(&auth, 0, sizeof(auth));
529
        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
530
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
Don Gagne's avatar
Don Gagne committed
531
        _sendMessage(msg);
James Goppert's avatar
James Goppert committed
532
    }
pixhawk's avatar
pixhawk committed
533 534
}

535
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
pixhawk's avatar
pixhawk committed
536 537
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
538
    _heartbeatsEnabled = enabled;
pixhawk's avatar
pixhawk committed
539 540 541
    emit heartbeatChanged(enabled);
}

542 543 544 545 546 547 548 549 550
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

551 552 553 554
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
555
    if (m_authEnabled != enable) {
556 557 558 559 560
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

561 562
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
563
    if (enabled != m_paramGuardEnabled) {
564 565 566 567 568
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

569 570
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
571
    if (enabled != m_actionGuardEnabled) {
572 573 574 575 576
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

577 578
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
579
    if (ms != m_paramRetransmissionTimeout) {
580 581 582 583 584 585 586
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
587
    if (ms != m_paramRewriteTimeout) {
588 589 590 591 592
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

593 594
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
595
    if (ms != m_actionRetransmissionTimeout) {
596 597 598 599 600
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
601 602 603
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
604
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
605 606
}

pixhawk's avatar
pixhawk committed
607 608 609 610 611 612 613
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
614 615
    _heartbeatRate = rate;
    _heartbeatTimer.setInterval(1000/_heartbeatRate);
pixhawk's avatar
pixhawk committed
616 617 618 619 620
}

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

Don Gagne's avatar
Don Gagne committed
624 625 626 627 628 629 630 631 632 633 634 635
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
636
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656
/// @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
657 658 659 660 661 662 663 664 665 666
    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;
            }

667 668 669 670 671
            if (_app->promptFlightDataSaveNotArmed()) {
                _logPromptForSave = true;
            }

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

Don Gagne's avatar
Don Gagne committed
673
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
674 675 676 677 678 679 680
        }
    }
}

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

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

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