MAVLinkProtocol.cc 25.7 KB
Newer Older
1
/*===================================================================
pixhawk's avatar
pixhawk committed
2 3 4 5
======================================================================*/

/**
 * @file
pixhawk's avatar
pixhawk committed
6 7
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
8 9 10 11 12 13 14
 */

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

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
15
#include <QApplication>
pixhawk's avatar
pixhawk committed
16
#include <QMessageBox>
17 18
#include <QSettings>
#include <QDesktopServices>
pixhawk's avatar
pixhawk committed
19 20 21 22 23 24

#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
25 26
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
27
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
28 29
#include "configuration.h"
#include "LinkManager.h"
30 31
#include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
32
#include "QGC.h"
pixhawk's avatar
pixhawk committed
33

34 35 36 37
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif

38

pixhawk's avatar
pixhawk committed
39 40 41 42 43
/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
MAVLinkProtocol::MAVLinkProtocol() :
44 45 46 47 48 49 50 51 52 53 54 55 56 57 58
    heartbeatTimer(new QTimer(this)),
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    m_heartbeatsEnabled(false),
    m_multiplexingEnabled(false),
    m_authEnabled(false),
    m_loggingEnabled(false),
    m_logfile(NULL),
    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)
pixhawk's avatar
pixhawk committed
59
{
60
    m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
61 62
    loadSettings();
    //start(QThread::LowPriority);
pixhawk's avatar
pixhawk committed
63 64 65
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);
66 67 68 69 70 71 72 73
    for (int i = 0; i < MAVLINK_COMM_NUM_BUFFERS; i++)
    {
        totalReceiveCounter[i] = 0;
        totalLossCounter[i] = 0;
        totalErrorCounter[i] = 0;
        currReceiveCounter[i] = 0;
        currLossCounter[i] = 0;
    }
74 75 76 77
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
lm's avatar
lm committed
78 79 80
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
81 82

    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
83 84
}

85 86 87 88 89 90
void MAVLinkProtocol::loadSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.sync();
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
91
    enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool());
92 93
    enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
    enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
94 95

    // Only set logfile if there is a name present in settings
96 97
    if (settings.contains("LOGFILE_NAME") && m_logfile == NULL)
    {
98
        m_logfile = new QFile(settings.value("LOGFILE_NAME").toString());
99 100 101
    }
    else if (m_logfile == NULL)
    {
102 103
        m_logfile = new QFile(QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink");
    }
104 105
    // Enable logging
    enableLogging(settings.value("LOGGING_ENABLED", m_loggingEnabled).toBool());
106 107 108

    // Only set system id if it was valid
    int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
109 110
    if (temp > 0 && temp < 256)
    {
111 112
        systemId = temp;
    }
113

114 115 116 117
    // Set auth key
    m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
    enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());

118 119 120 121 122 123 124
    // 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();
125 126 127 128 129 130 131 132 133 134
    settings.endGroup();
}

void MAVLinkProtocol::storeSettings()
{
    // Store settings
    QSettings settings;
    settings.beginGroup("QGC_MAVLINK_PROTOCOL");
    settings.setValue("HEARTBEATS_ENABLED", m_heartbeatsEnabled);
    settings.setValue("LOGGING_ENABLED", m_loggingEnabled);
135 136
    settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
    settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
137
    settings.setValue("GCS_SYSTEM_ID", systemId);
138 139
    settings.setValue("GCS_AUTH_KEY", m_authKey);
    settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
140 141
    if (m_logfile)
    {
142 143 144
        // Logfile exists, store the name
        settings.setValue("LOGFILE_NAME", m_logfile->fileName());
    }
145 146 147 148
    // 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);
149 150 151 152 153
    settings.endGroup();
    settings.sync();
    //qDebug() << "Storing settings!";
}

pixhawk's avatar
pixhawk committed
154 155
MAVLinkProtocol::~MAVLinkProtocol()
{
156
    storeSettings();
157 158 159 160
    if (m_logfile)
    {
        if (m_logfile->isOpen())
        {
161 162 163
            m_logfile->flush();
            m_logfile->close();
        }
pixhawk's avatar
pixhawk committed
164
        delete m_logfile;
165
        m_logfile = NULL;
pixhawk's avatar
pixhawk committed
166
    }
pixhawk's avatar
pixhawk committed
167 168
}

pixhawk's avatar
pixhawk committed
169 170
QString MAVLinkProtocol::getLogfileName()
{
171 172
    if (m_logfile)
    {
173
        return m_logfile->fileName();
174 175 176
    }
    else
    {
177
        return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
178
    }
pixhawk's avatar
pixhawk committed
179 180
}

181 182 183 184 185 186 187 188 189 190
void MAVLinkProtocol::linkStatusChanged(bool connected)
{
    LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());

    if (link) {
        if (connected) {
            // Send command to start MAVLink
            // XXX hacky but safe
            // Start NSH
            const char init[] = {0x0d, 0x0d, 0x0d};
Lorenz Meier's avatar
Lorenz Meier committed
191
            link->writeBytes(init, sizeof(init));
192 193 194 195 196 197 198 199 200 201 202 203 204 205 206

            // Stop any running mavlink instance
            char* cmd = "mavlink stop\n";
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 2);
            cmd = "uorb start";
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 2);
            cmd = "sh /etc/init.d/rc.usb\n";
            link->writeBytes(cmd, strlen(cmd));
            link->writeBytes(init, 4);
        }
    }
}

pixhawk's avatar
pixhawk committed
207 208 209 210 211 212 213 214
/**
 * The bytes are copied by calling the LinkInterface::readBytes() method.
 * 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
 **/
215
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
216
{
217
//    receiveMutex.lock();
pixhawk's avatar
pixhawk committed
218 219
    mavlink_message_t message;
    mavlink_status_t status;
220

221 222 223
    // Cache the link ID for common use.
    int linkId = link->getId();

224 225
    static int mavlink09Count = 0;
    static bool decodedFirstPacket = false;
226
    static bool warnedUser = false;
227

228
    // FIXME: Add check for if link->getId() >= MAVLINK_COMM_NUM_BUFFERS
229
    for (int position = 0; position < b.size(); position++) {
230
        unsigned int decodeState = mavlink_parse_char(linkId, (uint8_t)(b[position]), &message, &status);
231 232

        if ((uint8_t)b[position] == 0x55) mavlink09Count++;
233
        if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
234
        {
235
            warnedUser = true;
236 237
            // Obviously the user tries to use a 0.9 autopilot
            // with QGroundControl built for version 1.0
238
            emit protocolStatusMessage("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.");
239
        }
pixhawk's avatar
pixhawk committed
240

241 242 243
        // Count parser errors as well.
        totalErrorCounter[linkId] += status.packet_rx_drop_count;

244 245
        if (decodeState == 1)
        {
246
            decodedFirstPacket = true;
247
#if defined(QGC_PROTOBUF_ENABLED)
LM's avatar
LM committed
248

249 250
            if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
            {
251 252 253 254 255 256
                mavlink_extended_message_t extended_message;

                extended_message.base_msg = message;

                // read extended header
                uint8_t* payload = reinterpret_cast<uint8_t*>(message.payload64);
LM's avatar
LM committed
257

258 259
                memcpy(&extended_message.extended_payload_len, payload + 3, 4);

LM's avatar
LM committed
260 261 262 263 264 265 266 267 268
                // Check if message is valid
                if
                 (b.size() != MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_EXTENDED_HEADER_LEN+ extended_message.extended_payload_len)
                {
                    //invalid message
                    qDebug() << "GOT INVALID EXTENDED MESSAGE, ABORTING";
                    return;
                }

269 270 271 272 273
                const uint8_t* extended_payload = reinterpret_cast<const uint8_t*>(b.constData()) + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_EXTENDED_HEADER_LEN;

                // copy extended payload data
                memcpy(extended_message.extended_payload, extended_payload, extended_message.extended_payload_len);

274 275
#if defined(QGC_USE_PIXHAWK_MESSAGES)

276 277 278 279 280 281
                if (protobufManager.cacheFragment(extended_message))
                {
                    std::tr1::shared_ptr<google::protobuf::Message> protobuf_msg;

                    if (protobufManager.getMessage(protobuf_msg))
                    {
282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317
                        const google::protobuf::Descriptor* descriptor = protobuf_msg->GetDescriptor();
                        if (!descriptor)
                        {
                            continue;
                        }

                        const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
                        if (!headerField)
                        {
                            continue;
                        }

                        const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
                        if (!headerDescriptor)
                        {
                            continue;
                        }

                        const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
                        if (!sourceSysIdField)
                        {
                            continue;
                        }

                        const google::protobuf::Reflection* reflection = protobuf_msg->GetReflection();
                        const google::protobuf::Message& headerMsg = reflection->GetMessage(*protobuf_msg, headerField);
                        const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();

                        int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);

                        UASInterface* uas = UASManager::instance()->getUASForId(source_sysid);

                        if (uas != NULL)
                        {
                            emit extendedMessageReceived(link, protobuf_msg);
                        }
318 319
                    }
                }
320
#endif
321 322 323 324

                position += extended_message.extended_payload_len;

                continue;
325 326 327
            }
#endif

pixhawk's avatar
pixhawk committed
328
            // Log data
329 330
            if (m_loggingEnabled && m_logfile)
            {
331
                uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)] = {0};
332
                quint64 time = QGC::groundTimeUsecs();
333
                memcpy(buf, (void*)&time, sizeof(quint64));
334
                // Write message to buffer
335 336 337 338
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
                //we need to write the maximum package length for having a
                //consistent file structure and beeing able to parse it again
                int len = MAVLINK_MAX_PACKET_LEN + sizeof(quint64);
339
                QByteArray b((const char*)buf, len);
Lorenz Meier's avatar
Lorenz Meier committed
340
                if(m_logfile->write(b) != len)
341
                {
342 343 344 345
                    emit protocolStatusMessage(tr("MAVLink Logging failed"), tr("Could not write to file %1, disabling logging.").arg(m_logfile->fileName()));
                    // Stop logging
                    enableLogging(false);
                }
pixhawk's avatar
pixhawk committed
346 347
            }

pixhawk's avatar
pixhawk committed
348 349 350
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
351

pixhawk's avatar
pixhawk committed
352 353 354
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
355 356
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
            {
pixhawk's avatar
pixhawk committed
357 358 359 360 361 362
                // ORDER MATTERS HERE!
                // The UAS object has first to be created and connected,
                // only then the rest of the application can be made aware
                // of its existence, as it only then can send and receive
                // it's first messages.

pixhawk's avatar
pixhawk committed
363
                // Check if the UAS has the same id like this system
364 365
                if (message.sysid == getSystemId())
                {
366
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
367 368
                }

369 370 371 372
                // Create a new UAS based on the heartbeat received
                // Todo dynamically load plugin at run-time for MAV
                // WIKISEARCH:AUTOPILOT_TYPE_INSTANTIATION

pixhawk's avatar
pixhawk committed
373
                // First create new UAS object
374 375
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
376 377
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
378
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
379 380

                // Check if the UAS has a different protocol version
381 382
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
                {
pixhawk's avatar
pixhawk committed
383
                    // Bring up dialog to inform user
384 385
                    if (!versionMismatchIgnore)
                    {
386
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
387
                                                   tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
388 389
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
390 391 392 393 394

                    // Ignore this message and continue gracefully
                    continue;
                }

395 396
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
397

pixhawk's avatar
pixhawk committed
398
            }
399 400

            // Only count message if UAS exists for this message
401 402
            if (uas != NULL)
            {
403

404
                // Increase receive counter
405 406
                totalReceiveCounter[linkId]++;
                currReceiveCounter[linkId]++;
407 408 409

                // Update last message sequence ID
                uint8_t expectedIndex;
410
                if (lastIndex[message.sysid][message.compid] == -1)
411
                {
412
                    lastIndex[message.sysid][message.compid] = message.seq;
413
                    expectedIndex = message.seq;
414
                }
415 416
                else
                {
417
                    // NOTE: Using uint8_t here auto-wraps the number around to 0.
418
                    expectedIndex = lastIndex[message.sysid][message.compid] + 1;
419 420 421
                }

                // Make some noise if a message was skipped
422
                //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "EXPECTED INDEX:" << expectedIndex << "SEQ" << message.seq;
423 424 425
                if (message.seq != expectedIndex)
                {
                    // Determine how many messages were skipped accounting for 0-wraparound
426
                    int16_t lostMessages = message.seq - expectedIndex;
427 428 429 430 431 432 433
                    if (lostMessages < 0)
                    {
                        // Usually, this happens in the case of an out-of order packet
                        lostMessages = 0;
                    }
                    else
                    {
LM's avatar
LM committed
434 435
                        // Console generates excessive load at high loss rates, needs better GUI visualization
                        //qDebug() << QString("Lost %1 messages for comp %4: expected sequence ID %2 but received %3.").arg(lostMessages).arg(expectedIndex).arg(message.seq).arg(message.compid);
436
                    }
437 438
                    totalLossCounter[linkId] += lostMessages;
                    currLossCounter[linkId] += lostMessages;
439
                }
440 441 442

                // Update the last sequence ID
                lastIndex[message.sysid][message.compid] = message.seq;
443

444
                // Update on every 32th packet
445
                if (totalReceiveCounter[linkId] % 32 == 0)
446
                {
447 448
                    // Calculate new loss ratio
                    // Receive loss
449
                    float receiveLoss = (double)currLossCounter[linkId]/(double)(currReceiveCounter[linkId]+currLossCounter[linkId]);
450
                    receiveLoss *= 100.0f;
451 452
                    currLossCounter[linkId] = 0;
                    currReceiveCounter[linkId] = 0;
pixhawk's avatar
pixhawk committed
453
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
454 455
                }

456 457 458 459
                // 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);
460 461

                // Multiplex message if enabled
462 463
                if (m_multiplexingEnabled)
                {
464 465 466 467
                    // Get all links connected to this unit
                    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

                    // Emit message on all links that are currently connected
468 469
                    foreach (LinkInterface* currLink, links)
                    {
470 471
                        // Only forward this message to the other links,
                        // not the link the message was received on
Lorenz Meier's avatar
Lorenz Meier committed
472
                        if (currLink != link) sendMessage(currLink, message, message.sysid, message.compid);
473 474
                    }
                }
475
            }
pixhawk's avatar
pixhawk committed
476 477 478 479 480 481 482 483 484 485 486 487
        }
    }
}

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

488
/** @return System id of this application */
489
int MAVLinkProtocol::getSystemId()
490
{
491 492 493 494 495 496
    return systemId;
}

void MAVLinkProtocol::setSystemId(int id)
{
    systemId = id;
497 498 499
}

/** @return Component id of this application */
500
int MAVLinkProtocol::getComponentId()
501
{
502
    return QGC::defaultComponentId;
503 504
}

pixhawk's avatar
pixhawk committed
505 506 507 508 509 510 511 512 513 514
/**
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(mavlink_message_t message)
{
    // Get all links connected to this unit
    QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);

    // Emit message on all links that are currently connected
    QList<LinkInterface*>::iterator i;
515 516
    for (i = links.begin(); i != links.end(); ++i)
    {
pixhawk's avatar
pixhawk committed
517
        sendMessage(*i, message);
Lorenz Meier's avatar
Lorenz Meier committed
518
        qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
519 520 521 522 523 524 525 526 527 528
    }
}

/**
 * @param link the link to send the message over
 * @param message message to send
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message)
{
    // Create buffer
Lorenz Meier's avatar
Lorenz Meier committed
529
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
530
    // Rewriting header to ensure correct link ID is set
lm's avatar
lm committed
531 532
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
pixhawk's avatar
pixhawk committed
533
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
534
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
535
    // If link is connected
536 537
    if (link->isConnected())
    {
pixhawk's avatar
pixhawk committed
538 539 540 541 542
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565
/**
 * @param link the link to send the message over
 * @param message message to send
 * @param systemid id of the system the message is originating from
 * @param componentid id of the component the message is originating from
 */
void MAVLinkProtocol::sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid)
{
    // Create buffer
    static uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    // Rewriting header to ensure correct link ID is set
    static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, systemid, componentid, link->getId(), message.len, messageKeys[message.msgid]);
    // 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
566 567 568 569 570 571 572
/**
 * 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()
{
Lorenz Meier's avatar
Lorenz Meier committed
573 574
    if (m_heartbeatsEnabled)
    {
pixhawk's avatar
pixhawk committed
575
        mavlink_message_t beat;
lm's avatar
lm committed
576
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
pixhawk's avatar
pixhawk committed
577 578
        sendMessage(beat);
    }
Lorenz Meier's avatar
Lorenz Meier committed
579 580
    if (m_authEnabled)
    {
James Goppert's avatar
James Goppert committed
581 582
        mavlink_message_t msg;
        mavlink_auth_key_t auth;
583
        memset(&auth, 0, sizeof(auth));
584
        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
585 586 587
        mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
        sendMessage(msg);
    }
pixhawk's avatar
pixhawk committed
588 589 590 591 592 593 594 595 596
}

/** @param enabled true to enable heartbeats emission at heartbeatRate, false to disable */
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
    m_heartbeatsEnabled = enabled;
    emit heartbeatChanged(enabled);
}

597 598 599 600 601 602 603 604 605
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
    bool changed = false;
    if (enabled != m_multiplexingEnabled) changed = true;

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

606 607 608 609
void MAVLinkProtocol::enableAuth(bool enable)
{
    bool changed = false;
    m_authEnabled = enable;
610
    if (m_authEnabled != enable) {
611 612 613 614 615
        changed = true;
    }
    if (changed) emit authChanged(m_authEnabled);
}

616 617
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
618
    if (enabled != m_paramGuardEnabled) {
619 620 621 622 623
        m_paramGuardEnabled = enabled;
        emit paramGuardChanged(m_paramGuardEnabled);
    }
}

624 625
void MAVLinkProtocol::enableActionGuard(bool enabled)
{
626
    if (enabled != m_actionGuardEnabled) {
627 628 629 630 631
        m_actionGuardEnabled = enabled;
        emit actionGuardChanged(m_actionGuardEnabled);
    }
}

632 633
void MAVLinkProtocol::setParamRetransmissionTimeout(int ms)
{
634
    if (ms != m_paramRetransmissionTimeout) {
635 636 637 638 639 640 641
        m_paramRetransmissionTimeout = ms;
        emit paramRetransmissionTimeoutChanged(m_paramRetransmissionTimeout);
    }
}

void MAVLinkProtocol::setParamRewriteTimeout(int ms)
{
642
    if (ms != m_paramRewriteTimeout) {
643 644 645 646 647
        m_paramRewriteTimeout = ms;
        emit paramRewriteTimeoutChanged(m_paramRewriteTimeout);
    }
}

648 649
void MAVLinkProtocol::setActionRetransmissionTimeout(int ms)
{
650
    if (ms != m_actionRetransmissionTimeout) {
651 652 653 654 655
        m_actionRetransmissionTimeout = ms;
        emit actionRetransmissionTimeoutChanged(m_actionRetransmissionTimeout);
    }
}

lm's avatar
lm committed
656 657
void MAVLinkProtocol::enableLogging(bool enabled)
{
658 659 660
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

661 662 663 664
    if (enabled)
    {
        if (m_logfile && m_logfile->isOpen())
        {
665 666 667
            m_logfile->flush();
            m_logfile->close();
        }
668 669 670 671 672

        if (m_logfile)
        {
            if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
            {
673 674
                emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot log to the file %1, please choose a different file. Stopping logging.").arg(m_logfile->fileName()));
                m_loggingEnabled = false;
675
            }
676
        }
677 678 679 680 681 682 683 684 685 686 687
        else
        {
            emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot start logging, no logfile selected."));
        }
    }
    else if (!enabled)
    {
        if (m_logfile)
        {
            if (m_logfile->isOpen())
            {
688 689 690
                m_logfile->flush();
                m_logfile->close();
            }
691
        }
lm's avatar
lm committed
692 693
    }
    m_loggingEnabled = enabled;
694
    if (changed) emit loggingChanged(enabled);
695 696 697 698
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
699 700
    if (!m_logfile)
    {
701
        m_logfile = new QFile(filename);
702 703 704
    }
    else
    {
705 706 707
        m_logfile->flush();
        m_logfile->close();
    }
708
    m_logfile->setFileName(filename);
709
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
710 711
}

lm's avatar
lm committed
712 713 714
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
715
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
716 717
}

pixhawk's avatar
pixhawk committed
718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733
/**
 * The default rate is 1 Hertz.
 *
 * @param rate heartbeat rate in hertz (times per second)
 */
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
    heartbeatRate = rate;
    heartbeatTimer->setInterval(1000/heartbeatRate);
}

/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
    return heartbeatRate;
}