MAVLinkProtocol.cc 18.1 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

pixhawk's avatar
pixhawk committed
10 11 12

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

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

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

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

42
Q_DECLARE_METATYPE(mavlink_message_t)
43

44
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
45

Don Gagne's avatar
Don Gagne committed
46 47 48
const char* MAVLinkProtocol::_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file
const char* MAVLinkProtocol::_logFileExtension = "mavlink";             ///< Extension for log files

pixhawk's avatar
pixhawk committed
49 50 51 52
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
53 54
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
55 56
    , m_enable_version_check(true)
    , versionMismatchIgnore(false)
57
    , systemId(255)
58
    , _current_version(100)
59
    , _radio_version_mismatch_count(0)
60 61
    , _logSuspendError(false)
    , _logSuspendReplay(false)
62
    , _vehicleWasArmed(false)
63 64 65
    , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
    , _linkMgr(NULL)
    , _multiVehicleManager(NULL)
pixhawk's avatar
pixhawk committed
66
{
67 68 69 70 71
    memset(&totalReceiveCounter, 0, sizeof(totalReceiveCounter));
    memset(&totalLossCounter, 0, sizeof(totalLossCounter));
    memset(&totalErrorCounter, 0, sizeof(totalErrorCounter));
    memset(&currReceiveCounter, 0, sizeof(currReceiveCounter));
    memset(&currLossCounter, 0, sizeof(currLossCounter));
pixhawk's avatar
pixhawk committed
72 73
}

74 75 76 77 78 79
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
    _closeLogFile();
}

80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97
void MAVLinkProtocol::setVersion(unsigned version)
{
    QList<LinkInterface*> links = _linkMgr->links();

    for (int i = 0; i < links.length(); i++) {
        mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(links[i]->mavlinkChannel());

        // Set flags for version
        if (version < 200) {
            mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        } else {
            mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
        }
    }

    _current_version = version;
}

98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);

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

   qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

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

121 122 123
   connect(this, &MAVLinkProtocol::protocolStatusMessage,   _app, &QGCApplication::criticalMessageBoxOnMainThread);
   connect(this, &MAVLinkProtocol::saveTelemetryLog,        _app, &QGCApplication::saveTelemetryLogOnMainThread);
   connect(this, &MAVLinkProtocol::checkTelemetrySavePath,  _app, &QGCApplication::checkTelemetrySavePathOnMainThread);
124

125 126
   connect(_multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkProtocol::_vehicleCountChanged);
   connect(_multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged);
127

128 129 130
   emit versionCheckChanged(m_enable_version_check);
}

131 132 133 134 135
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
136
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
137 138 139

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
140 141
    if (temp > 0 && temp < 256)
    {
142 143 144 145 146 147 148 149 150
        systemId = temp;
    }
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
151
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
152
    settings.setValue("GCS_SYSTEM_ID", systemId);
153
    // Parameter interface settings
154 155
}

156
void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link)
157
{
158
    int channel = link->mavlinkChannel();
159 160 161 162 163
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
164
    link->setDecodedFirstMavlinkPacket(false);
165 166
}

pixhawk's avatar
pixhawk committed
167 168 169 170 171 172 173
/**
 * 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
 **/
174
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
175
{
Don Gagne's avatar
Don Gagne committed
176 177 178
    // 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.
179
    if (!_linkMgr->containsLink(link)) {
Don Gagne's avatar
Don Gagne committed
180 181
        return;
    }
Gus Grubba's avatar
Gus Grubba committed
182

183
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
184 185
    mavlink_message_t message;
    mavlink_status_t status;
186

187
    int mavlinkChannel = link->mavlinkChannel();
188

189 190 191
    static int nonmavlinkCount = 0;
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
192

193
    for (int position = 0; position < b.size(); position++) {
194
        unsigned int decodeState = mavlink_parse_char(mavlinkChannel, (uint8_t)(b[position]), &message, &status);
195

196
        if (decodeState == 0 && !link->decodedFirstMavlinkPacket())
197 198
        {
            nonmavlinkCount++;
199
            if (nonmavlinkCount > 1000 && !warnedUserNonMavlink)
200
            {
201
                // 500 bytes with no mavlink message. Are we connected to a mavlink capable device?
202 203 204 205 206 207 208 209
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
210 211 212 213 214 215
                    // Disconnect the link since its some other device and
                    // QGC clinging on to it and feeding it data might have unintended
                    // side effects (e.g. if its a modem)
                    qDebug() << "disconnected link" << link->getName() << "as it contained no MAVLink data";
                    QMetaObject::invokeMethod(_linkMgr, "disconnectLink", Q_ARG( LinkInterface*, link ) );
                    return;
216 217 218
                }
            }
        }
219 220
        if (decodeState == 1)
        {
221
            if (!link->decodedFirstMavlinkPacket()) {
222
                link->setDecodedFirstMavlinkPacket(true);
223 224
                mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
                if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
225
                    qDebug() << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
226
                    mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
227 228 229

                    // Set all links to v2
                    setVersion(200);
230
                }
Don Gagne's avatar
Don Gagne committed
231 232
            }

pixhawk's avatar
pixhawk committed
233
            // Log data
Don Gagne's avatar
Don Gagne committed
234
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
                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.
250
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
251
                if(_tempLogFile.write(b) != len)
252
                {
253
                    // If there's an error logging data, raise an alert and stop logging.
254
                    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
255 256
                    _stopLogging();
                    _logSuspendError = true;
257
                }
Gus Grubba's avatar
Gus Grubba committed
258

Don Gagne's avatar
Don Gagne committed
259
                // Check for the vehicle arming going by. This is used to trigger log save.
260
                if (!_vehicleWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
261 262 263
                    mavlink_heartbeat_t state;
                    mavlink_msg_heartbeat_decode(&message, &state);
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
264
                        _vehicleWasArmed = true;
Don Gagne's avatar
Don Gagne committed
265 266
                    }
                }
pixhawk's avatar
pixhawk committed
267 268
            }

269
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
270
                _startLogging();
271 272
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
273 274 275 276 277 278 279 280
                emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.autopilot, heartbeat.type);
            }

            if (message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) {
                _startLogging();
                mavlink_high_latency2_t highLatency2;
                mavlink_msg_high_latency2_decode(&message, &highLatency2);
                emit vehicleHeartbeatInfo(link, message.sysid, message.compid, highLatency2.autopilot, highLatency2.type);
pixhawk's avatar
pixhawk committed
281
            }
282

283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302
            // Detect if we are talking to an old radio not supporting v2
            mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
            if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
                if ((mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)
                && !(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {

                    _radio_version_mismatch_count++;
                }
            }

            if (_radio_version_mismatch_count == 5) {
                // Warn the user if the radio continues to send v1 while the link uses v2
                emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Detected radio still using MAVLink v1.0 on a link with MAVLink v2.0 enabled. Please upgrade the radio firmware."));
                // Ensure the warning can't get stuck
                _radio_version_mismatch_count++;
                // Flick link back to v1
                qDebug() << "Switching outbound to mavlink 1.0 due to incoming mavlink 1.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
                mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            }

303
            // Increase receive counter
304 305
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
306

307 308 309 310
            // 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);
311

312 313 314
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
315

316 317
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
318

319 320 321 322 323
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
324

325
                // And log how many were lost for all time and just this timestep
326 327
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
328
            }
329

330 331
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
332

333
            // Update on every 32th packet
334
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
335 336 337
            {
                // Calculate new loss ratio
                // Receive loss
338 339
                float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
                receiveLossPercent *= 100.0f;
340 341
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
342 343
                emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
                emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
344
            }
345

346 347 348 349
            // 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);
pixhawk's avatar
pixhawk committed
350 351 352 353 354 355 356 357 358 359 360 361
        }
    }
}

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

362
/** @return System id of this application */
363
int MAVLinkProtocol::getSystemId()
364
{
365 366 367 368 369 370
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
371 372 373
}

/** @return Component id of this application */
374
int MAVLinkProtocol::getComponentId()
375
{
376
    return 0;
377 378
}

lm's avatar
lm committed
379 380 381
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
382
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
383 384
}

385
void MAVLinkProtocol::_vehicleCountChanged(void)
Don Gagne's avatar
Don Gagne committed
386
{
387
    int count = _multiVehicleManager->vehicles()->count();
Don Gagne's avatar
Don Gagne committed
388 389 390
    if (count == 0) {
        // Last vehicle is gone, close out logging
        _stopLogging();
391
        _radio_version_mismatch_count = 0;
Don Gagne's avatar
Don Gagne committed
392 393 394
    }
}

Don Gagne's avatar
Don Gagne committed
395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
/// @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)
{
414
    //-- Are we supposed to write logs?
415 416 417
    if (qgcApp()->runningUnitTests()) {
        return;
    }
418 419 420 421 422 423 424 425
#ifdef __mobile__
    //-- Mobile build don't write to /tmp unless told to do so
    if (!_app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) {
        return;
    }
#endif
    //-- Log is always written to a temp file. If later the user decides they want
    //   it, it's all there for them.
Don Gagne's avatar
Don Gagne committed
426 427 428 429 430 431 432 433 434 435
    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;
            }

436
            qDebug() << "Temp log" << _tempLogFile.fileName();
437
            emit checkTelemetrySavePath();
438

Don Gagne's avatar
Don Gagne committed
439
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
440 441 442 443 444 445
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
446 447 448 449 450 451 452 453
    if (_tempLogFile.isOpen()) {
        if (_closeLogFile()) {
            if ((_vehicleWasArmed || _app->toolbox()->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) &&
                _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) {
                emit saveTelemetryLog(_tempLogFile.fileName());
            } else {
                QFile::remove(_tempLogFile.fileName());
            }
454
        }
Don Gagne's avatar
Don Gagne committed
455
    }
456
    _vehicleWasArmed = false;
Don Gagne's avatar
Don Gagne committed
457 458 459 460 461
}

/// @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.
462
void MAVLinkProtocol::checkForLostLogFiles(void)
Don Gagne's avatar
Don Gagne committed
463 464
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
Gus Grubba's avatar
Gus Grubba committed
465

Don Gagne's avatar
Don Gagne committed
466 467
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
468
    //qDebug() << "Orphaned log file count" << fileInfoList.count();
Gus Grubba's avatar
Gus Grubba committed
469

Don Gagne's avatar
Don Gagne committed
470
    foreach(const QFileInfo fileInfo, fileInfoList) {
471
        //qDebug() << "Orphaned log file" << fileInfo.filePath();
Don Gagne's avatar
Don Gagne committed
472 473 474 475 476
        if (fileInfo.size() == 0) {
            // Delete all zero length files
            QFile::remove(fileInfo.filePath());
            continue;
        }
477
        emit saveTelemetryLog(fileInfo.filePath());
Don Gagne's avatar
Don Gagne committed
478 479 480 481 482 483 484
    }
}

void MAVLinkProtocol::suspendLogForReplay(bool suspend)
{
    _logSuspendReplay = suspend;
}
485 486 487 488

void MAVLinkProtocol::deleteTempLogFiles(void)
{
    QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
Gus Grubba's avatar
Gus Grubba committed
489

490 491
    QString filter(QString("*.%1").arg(_logFileExtension));
    QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
Gus Grubba's avatar
Gus Grubba committed
492

493 494 495 496
    foreach(const QFileInfo fileInfo, fileInfoList) {
        QFile::remove(fileInfo.filePath());
    }
}
497