MAVLinkProtocol.cc 18.4 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"
pixhawk's avatar
pixhawk committed
38

39
Q_DECLARE_METATYPE(mavlink_message_t)
40

41
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
42

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

pixhawk's avatar
pixhawk committed
48 49 50 51
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
52 53 54 55
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
    : QGCTool(app)
    , m_enable_version_check(true)
    , versionMismatchIgnore(false)
56
    , systemId(255)
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
    , _linkMgr(NULL)
    , _multiVehicleManager(NULL)
pixhawk's avatar
pixhawk committed
65
{
66 67 68 69 70
    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
71 72
}

73 74 75
MAVLinkProtocol::~MAVLinkProtocol()
{
    storeSettings();
Gus Grubba's avatar
Gus Grubba committed
76

Don Gagne's avatar
Don Gagne committed
77
#ifndef __mobile__
78
    _closeLogFile();
Don Gagne's avatar
Don Gagne committed
79
#endif
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
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);
106
#ifndef __mobile__
107
   connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);
108
#endif
109

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

112 113 114
   emit versionCheckChanged(m_enable_version_check);
}

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

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

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

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

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

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

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

172
    static int mavlink09Count = 0;
173
    static int nonmavlinkCount = 0;
174
    static bool decodedFirstPacket = false;
175
    static bool warnedUser = false;
176 177
    static bool checkedUserNonMavlink = false;
    static bool warnedUserNonMavlink = false;
178

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

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
183
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
184
        {
185
            warnedUser = true;
186 187
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
188 189 190 191
            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."));
192
        }
pixhawk's avatar
pixhawk committed
193

194 195 196
        if (decodeState == 0 && !decodedFirstPacket)
        {
            nonmavlinkCount++;
197
            if (nonmavlinkCount > 2000 && !warnedUserNonMavlink)
198
            {
199
                //2000 bytes with no mavlink message. Are we connected to a mavlink capable device?
200 201 202 203 204 205 206 207
                if (!checkedUserNonMavlink)
                {
                    link->requestReset();
                    checkedUserNonMavlink = true;
                }
                else
                {
                    warnedUserNonMavlink = true;
208 209
                    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."));
210 211 212
                }
            }
        }
213 214
        if (decodeState == 1)
        {
215
            decodedFirstPacket = true;
216

Gus Grubba's avatar
Gus Grubba committed
217 218
            /*
             * Handled in Vehicle.cc now.
Don Gagne's avatar
Don Gagne committed
219 220
            mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
            if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
221
                qDebug() << "switch to mavlink 2.0" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
Don Gagne's avatar
Don Gagne committed
222 223
                mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            } else if ((mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && !(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
224
                qDebug() << "switch to mavlink 1.0" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags;
Don Gagne's avatar
Don Gagne committed
225 226
                mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            }
Gus Grubba's avatar
Gus Grubba committed
227
            */
Don Gagne's avatar
Don Gagne committed
228

229 230 231 232 233
            if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
            {
                // process telemetry status message
                mavlink_radio_status_t rstatus;
                mavlink_msg_radio_status_decode(&message, &rstatus);
234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
                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);
250 251 252
                } else {
                    rssi = (int8_t) rstatus.rssi;
                    remrssi = (int8_t) rstatus.remrssi;
253
                }
254

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

Don Gagne's avatar
Don Gagne committed
259
#ifndef __mobile__
pixhawk's avatar
pixhawk committed
260
            // Log data
Gus Grubba's avatar
Gus Grubba committed
261

Don Gagne's avatar
Don Gagne committed
262
            if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
                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.
278
                QByteArray b((const char*)buf, len);
Don Gagne's avatar
Don Gagne committed
279
                if(_tempLogFile.write(b) != len)
280
                {
281
                    // If there's an error logging data, raise an alert and stop logging.
282
                    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
283 284
                    _stopLogging();
                    _logSuspendError = true;
285
                }
Gus Grubba's avatar
Gus Grubba committed
286

Don Gagne's avatar
Don Gagne committed
287
                // Check for the vehicle arming going by. This is used to trigger log save.
288
                if (!_logPromptForSave && message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
289 290 291
                    mavlink_heartbeat_t state;
                    mavlink_msg_heartbeat_decode(&message, &state);
                    if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
292
                        _logPromptForSave = true;
Don Gagne's avatar
Don Gagne committed
293 294
                    }
                }
pixhawk's avatar
pixhawk committed
295
            }
Don Gagne's avatar
Don Gagne committed
296
#endif
pixhawk's avatar
pixhawk committed
297

298
            if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
Don Gagne's avatar
Don Gagne committed
299 300 301 302 303
#ifndef __mobile__
                // Start loggin on first heartbeat
                _startLogging();
#endif

304 305
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
Don Gagne's avatar
Don Gagne committed
306
                emit vehicleHeartbeatInfo(link, message.sysid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
pixhawk's avatar
pixhawk committed
307
            }
308

309
            // Increase receive counter
310 311
            totalReceiveCounter[mavlinkChannel]++;
            currReceiveCounter[mavlinkChannel]++;
312

313 314 315 316
            // 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);
317

318 319 320
            // And if we didn't encounter that sequence number, record the error
            if (message.seq != expectedSeq)
            {
321

322 323
                // Determine how many messages were skipped
                int lostMessages = message.seq - expectedSeq;
324

325 326 327 328 329
                // Out of order messages or wraparound can cause this, but we just ignore these conditions for simplicity
                if (lostMessages < 0)
                {
                    lostMessages = 0;
                }
330

331
                // And log how many were lost for all time and just this timestep
332 333
                totalLossCounter[mavlinkChannel] += lostMessages;
                currLossCounter[mavlinkChannel] += lostMessages;
334
            }
335

336 337
            // And update the last sequence number for this system/component pair
            lastIndex[message.sysid][message.compid] = expectedSeq;
338

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

352 353 354 355
            // 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
356 357 358 359 360 361 362 363 364 365 366 367
        }
    }
}

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

368
/** @return System id of this application */
369
int MAVLinkProtocol::getSystemId()
370
{
371 372 373 374 375 376
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
377 378 379
}

/** @return Component id of this application */
380
int MAVLinkProtocol::getComponentId()
381
{
382
    return 0;
383 384
}

lm's avatar
lm committed
385 386 387
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
388
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
389 390
}

Don Gagne's avatar
Don Gagne committed
391 392 393 394 395 396 397 398 399 400 401 402
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
403
#ifndef __mobile__
Don Gagne's avatar
Don Gagne committed
404 405 406 407 408 409 410 411 412 413 414 415 416 417
/// @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
418

Don Gagne's avatar
Don Gagne committed
419 420 421 422 423
    return false;
}

void MAVLinkProtocol::_startLogging(void)
{
Don Gagne's avatar
Don Gagne committed
424 425 426 427 428 429 430 431 432 433
    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;
            }

434 435 436 437 438
            if (_app->promptFlightDataSaveNotArmed()) {
                _logPromptForSave = true;
            }

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

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

void MAVLinkProtocol::_stopLogging(void)
{
    if (_closeLogFile()) {
448
        // If the signals are not connected it means we are running a unit test. In that case just delete log files
449
        if (_logPromptForSave && _app->promptFlightDataSave()) {
450 451 452 453
            emit saveTempFlightDataLog(_tempLogFile.fileName());
        } else {
            QFile::remove(_tempLogFile.fileName());
        }
Don Gagne's avatar
Don Gagne committed
454
    }
455
    _logPromptForSave = false;
Don Gagne's avatar
Don Gagne committed
456 457 458 459 460
}

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

Don Gagne's avatar
Don Gagne committed
465 466 467
    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
468

Don Gagne's avatar
Don Gagne committed
469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489
    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;
}
490 491 492 493

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

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

498 499 500 501
    foreach(const QFileInfo fileInfo, fileInfoList) {
        QFile::remove(fileInfo.filePath());
    }
}
Don Gagne's avatar
Don Gagne committed
502
#endif