MAVLinkProtocol.cc 17.3 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>
pixhawk's avatar
pixhawk committed
27 28 29 30 31 32

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

40
Q_DECLARE_METATYPE(mavlink_message_t)
41

42
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
43

Don Gagne's avatar
Don Gagne committed
44
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
45 46
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
47
#endif
Don Gagne's avatar
Don Gagne committed
48

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 55 56
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
    : QGCTool(app)
    , m_enable_version_check(true)
    , versionMismatchIgnore(false)
57
    , systemId(255)
Don Gagne's avatar
Don Gagne committed
58
#ifndef __mobile__
59 60
    , _logSuspendError(false)
    , _logSuspendReplay(false)
61
    , _vehicleWasArmed(false)
62
    , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
Don Gagne's avatar
Don Gagne committed
63
#endif
64 65
    , _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
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
Gus Grubba's avatar
Gus Grubba committed
77

Don Gagne's avatar
Don Gagne committed
78
#ifndef __mobile__
79
    _closeLogFile();
Don Gagne's avatar
Don Gagne committed
80
#endif
81 82
}

83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106
void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);

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

   qRegisterMetaType<mavlink_message_t>("mavlink_message_t");

   loadSettings();

   // All the *Counter variables are not initialized here, as they should be initialized
   // on a per-link basis before those links are used. @see resetMetadataForLink().

   // Initialize the list for tracking dropped messages to invalid.
   for (int i = 0; i < 256; i++)
   {
       for (int j = 0; j < 256; j++)
       {
           lastIndex[i][j] = -1;
       }
   }

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

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

113 114 115
   emit versionCheckChanged(m_enable_version_check);
}

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

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

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
136
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
137
    settings.setValue("GCS_SYSTEM_ID", systemId);
138
    // Parameter interface settings
139 140
}

141 142
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
143
    int channel = link->mavlinkChannel();
144 145 146 147 148
    totalReceiveCounter[channel] = 0;
    totalLossCounter[channel] = 0;
    totalErrorCounter[channel] = 0;
    currReceiveCounter[channel] = 0;
    currLossCounter[channel] = 0;
149 150
}

pixhawk's avatar
pixhawk committed
151 152 153 154 155 156 157
/**
 * 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
 **/
158
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
159
{
Don Gagne's avatar
Don Gagne committed
160 161 162
    // 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.
163
    if (!_linkMgr->containsLink(link)) {
Don Gagne's avatar
Don Gagne committed
164 165
        return;
    }
Gus Grubba's avatar
Gus Grubba committed
166

167
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
168 169
    mavlink_message_t message;
    mavlink_status_t status;
170

171
    int mavlinkChannel = link->mavlinkChannel();
172

173 174 175
    static int nonmavlinkCount = 0;
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
176

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

180
        if (decodeState == 0 && !link->decodedFirstMavlinkPacket())
181 182
        {
            nonmavlinkCount++;
183
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
184
            {
185
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
186 187 188 189 190 191 192 193
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
194 195
                    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."));
196 197 198
                }
            }
        }
199 200
        if (decodeState == 1)
        {
201
            if (!link->decodedFirstMavlinkPacket()) {
202 203
                mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
                if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
204
                    qDebug() << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
205 206
                    mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
                }
207
                link->setDecodedFirstMavlinkPacket(true);
Don Gagne's avatar
Don Gagne committed
208 209
            }

210 211 212 213 214
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);
215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230
                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);
231 232 233
                } else {
                    rssi = (int8_t) rstatus.rssi;
                    remrssi = (int8_t) rstatus.remrssi;
234
                }
235

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

Don Gagne's avatar
Don Gagne committed
240
#ifndef __mobile__
pixhawk's avatar
pixhawk committed
241
            // Log data
Gus Grubba's avatar
Gus Grubba committed
242

Don Gagne's avatar
Don Gagne committed
243
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
244 245 246 247 248 249 250 251 252 253 254 255 256 257 258
                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.
259
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
260
                if(_tempLogFile.write(b) != len)
261
                {
262
                    // If there's an error logging data, raise an alert and stop logging.
263
                    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
264 265
                    _stopLogging();
                    _logSuspendError = true;
266
                }
Gus Grubba's avatar
Gus Grubba committed
267

Don Gagne's avatar
Don Gagne committed
268
                // Check for the vehicle arming going by. This is used to trigger log save.
269
                if (!_vehicleWasArmed && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
270 271 272
                    mavlink_heartbeat_t state;
                    mavlink_msg_heartbeat_decode(&message, &state);
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
273
                        _vehicleWasArmed = true;
Don Gagne's avatar
Don Gagne committed
274 275
                    }
                }
pixhawk's avatar
pixhawk committed
276
            }
Don Gagne's avatar
Don Gagne committed
277
#endif
pixhawk's avatar
pixhawk committed
278

279
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
280 281 282 283 284
#ifndef __mobile__
                // Start loggin on first heartbeat
                _startLogging();
#endif

285 286
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
287
                emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
pixhawk's avatar
pixhawk committed
288
            }
289

290
            // Increase receive counter
291 292
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
293

294 295 296 297
            // 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);
298

299 300 301
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
302

303 304
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
305

306 307 308 309 310
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
311

312
                // And log how many were lost for all time and just this timestep
313 314
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
315
            }
316

317 318
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
319

320
            // Update on every 32th packet
321
            if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0)
322 323 324
            {
                // Calculate new loss ratio
                // Receive loss
325 326
                float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
                receiveLossPercent *= 100.0f;
327 328
                currLossCounter[mavlinkChannel] = 0;
                currReceiveCounter[mavlinkChannel] = 0;
329 330
                emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
                emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
331
            }
332

333 334 335 336
            // 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
337 338 339 340 341 342 343 344 345 346 347 348
        }
    }
}

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

349
/** @return System id of this application */
350
int MAVLinkProtocol::getSystemId()
351
{
352 353 354 355 356 357
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
358 359 360
}

/** @return Component id of this application */
361
int MAVLinkProtocol::getComponentId()
362
{
363
    return 0;
364 365
}

lm's avatar
lm committed
366 367 368
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
369
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
370 371
}

Don Gagne's avatar
Don Gagne committed
372 373 374 375 376 377 378 379 380 381 382 383
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
384
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
385 386 387 388 389 390 391 392 393 394 395 396 397 398
/// @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;
        }
    }
Gus Grubba's avatar
Gus Grubba committed
399

Don Gagne's avatar
Don Gagne committed
400 401 402 403 404
    return false;
}

void MAVLinkProtocol::_startLogging(void)
{
Don Gagne's avatar
Don Gagne committed
405 406 407 408 409 410 411 412 413 414
    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;
            }

415
            qDebug() << "Temp log" << _tempLogFile.fileName();
416

Don Gagne's avatar
Don Gagne committed
417
            _logSuspendError = false;
Don Gagne's avatar
Don Gagne committed
418 419 420 421 422 423 424
        }
    }
}

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
425
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
426
        SettingsManager* settingsManager = _app->toolbox()->settingsManager();
427
        if ((_vehicleWasArmed || settingsManager->appSettings()->promptFlightTelemetrySaveNotArmed()->rawValue().toBool()) && settingsManager->appSettings()->promptFlightTelemetrySave()->rawValue().toBool()) {
428 429 430 431
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
432
    }
433
    _vehicleWasArmed = false;
Don Gagne's avatar
Don Gagne committed
434 435 436 437 438
}

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

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

Don Gagne's avatar
Don Gagne committed
447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467
    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;
}
468 469 470 471

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

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

476 477 478 479
    foreach(const QFileInfo fileInfo, fileInfoList) {
        QFile::remove(fileInfo.filePath());
    }
}
Don Gagne's avatar
Don Gagne committed
480
#endif