MAVLinkProtocol.cc 13.2 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>
pixhawk's avatar
pixhawk committed
17 18 19 20 21 22 23

#include "MG.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
24 25
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
26
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
27 28
#include "configuration.h"
#include "LinkManager.h"
29
//#include "MainWindow.h"
30 31
#include "QGCMAVLink.h"
#include "QGCMAVLinkUASFactory.h"
32
#include "QGC.h"
pixhawk's avatar
pixhawk committed
33 34 35 36 37 38 39 40

/**
 * The default constructor will create a new MAVLink object sending heartbeats at
 * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links.
 */
MAVLinkProtocol::MAVLinkProtocol() :
        heartbeatTimer(new QTimer(this)),
        heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
lm's avatar
lm committed
41 42
        m_heartbeatsEnabled(false),
        m_loggingEnabled(false),
43
        m_logfile(new QFile(QCoreApplication::applicationDirPath()+"/mavlink_packetlog.mavlink")),
lm's avatar
lm committed
44
        m_enable_version_check(true),
45
        versionMismatchIgnore(false)
pixhawk's avatar
pixhawk committed
46 47 48 49 50
{
    start(QThread::LowPriority);
    // Start heartbeat timer, emitting a heartbeat at the configured rate
    connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
    heartbeatTimer->start(1000/heartbeatRate);
lm's avatar
lm committed
51 52
    totalReceiveCounter = 0;
    totalLossCounter = 0;
53 54
    currReceiveCounter = 0;
    currLossCounter = 0;
lm's avatar
lm committed
55 56 57 58 59 60 61
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
            lastIndex[i][j] = -1;
        }
    }
lm's avatar
lm committed
62 63

    emit versionCheckChanged(m_enable_version_check);
pixhawk's avatar
pixhawk committed
64 65 66 67
}

MAVLinkProtocol::~MAVLinkProtocol()
{
pixhawk's avatar
pixhawk committed
68 69
    if (m_logfile)
    {
70
        m_logfile->flush();
pixhawk's avatar
pixhawk committed
71 72 73
        m_logfile->close();
        delete m_logfile;
    }
pixhawk's avatar
pixhawk committed
74 75 76 77 78 79
}



void MAVLinkProtocol::run()
{
lm's avatar
lm committed
80
    exec();
pixhawk's avatar
pixhawk committed
81 82
}

pixhawk's avatar
pixhawk committed
83 84
QString MAVLinkProtocol::getLogfileName()
{
85
    return m_logfile->fileName();
pixhawk's avatar
pixhawk committed
86 87
}

pixhawk's avatar
pixhawk committed
88 89 90 91 92 93 94 95
/**
 * 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
 **/
96
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
97 98 99 100
{
    receiveMutex.lock();
    mavlink_message_t message;
    mavlink_status_t status;
101
    for (int position = 0; position < b.size(); position++)
pixhawk's avatar
pixhawk committed
102
    {
103
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed
104 105 106

        if (decodeState == 1)
        {
pixhawk's avatar
pixhawk committed
107 108 109
            // Log data
            if (m_loggingEnabled)
            {
lm's avatar
lm committed
110
                const int len = MAVLINK_MAX_PACKET_LEN+sizeof(quint64);
111 112
                uint8_t buf[len];
                quint64 time = QGC::groundTimeUsecs();
113
                memcpy(buf, (void*)&time, sizeof(quint64));
114 115 116
                //                int packetlen =
//                quint64 checktime = *((quint64*)buf);
//                qDebug() << "TIME" << time << "CHECKTIME:" << checktime;
117
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
118 119 120 121
                QByteArray b((const char*)buf, len);
                //int packetlen =
                if(m_logfile->write(b) < MAVLINK_MAX_PACKET_LEN+sizeof(quint64)) qDebug() << "WRITING TO LOG FAILED!";
                //qDebug() << "WROTE LOGFILE";
pixhawk's avatar
pixhawk committed
122 123
            }

pixhawk's avatar
pixhawk committed
124 125 126 127 128 129
            // ORDER MATTERS HERE!
            // If the matching UAS object does not yet exist, it has to be created
            // before emitting the packetReceived signal
            UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);

            // Check and (if necessary) create UAS object
130
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
pixhawk's avatar
pixhawk committed
131 132 133 134 135 136 137
            {
                // 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
138
                // Check if the UAS has the same id like this system
139 140
                if (message.sysid == getSystemId())
                {
141
                    emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
142 143
                }

144 145 146 147
                // 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
148
                // First create new UAS object
149 150
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
151 152
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
153
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
154 155

                // Check if the UAS has a different protocol version
lm's avatar
lm committed
156
                if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
pixhawk's avatar
pixhawk committed
157 158
                {
                    // Bring up dialog to inform user
159 160 161
                    if (!versionMismatchIgnore)
                    {
                        emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
162
                                                   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));
163 164
                        versionMismatchIgnore = true;
                    }
pixhawk's avatar
pixhawk committed
165 166 167 168 169

                    // Ignore this message and continue gracefully
                    continue;
                }

170 171
                // Create a new UAS object
                uas = QGCMAVLinkUASFactory::createUAS(this, link, message.sysid, &heartbeat);
pixhawk's avatar
pixhawk committed
172
            }
173 174 175

            // Only count message if UAS exists for this message
            if (uas != NULL)
lm's avatar
lm committed
176
            {
177 178 179 180 181 182
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
                if (lastIndex[message.sysid][message.compid] == -1)
lm's avatar
lm committed
183
                {
184
                    lastIndex[message.sysid][message.compid] = message.seq;
lm's avatar
lm committed
185 186
                }
                else
lm's avatar
lm committed
187
                {
Mariano Lizarraga's avatar
Mariano Lizarraga committed
188
                    // TODO: This if-else block can (should) be greatly simplified
lm's avatar
lm committed
189 190 191 192 193 194 195 196
                    if (lastIndex[message.sysid][message.compid] == 255)
                    {
                        lastIndex[message.sysid][message.compid] = 0;
                    }
                    else
                    {
                        lastIndex[message.sysid][message.compid]++;
                    }
197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223

                    int safeguard = 0;
                    //qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
                    while(lastIndex[message.sysid][message.compid] != message.seq && safeguard < 255)
                    {
                        if (lastIndex[message.sysid][message.compid] == 255)
                        {
                            lastIndex[message.sysid][message.compid] = 0;
                        }
                        else
                        {
                            lastIndex[message.sysid][message.compid]++;
                        }
                        totalLossCounter++;
                        currLossCounter++;
                        safeguard++;
                    }
                }
                //            if (lastIndex.contains(message.sysid))
                //            {
                //                QMap<int, int>* lastCompIndex = lastIndex.value(message.sysid);
                //                if (lastCompIndex->contains(message.compid))
                //                while (lastCompIndex->value(message.compid, 0)+1 )
                //            }
                //if ()

                // If a new loss was detected or we just hit one 128th packet step
lm's avatar
lm committed
224
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0))
225 226 227 228 229 230 231 232
                {
                    // Calculate new loss ratio
                    // Receive loss
                    float receiveLoss = (double)currLossCounter/(double)(currReceiveCounter+currLossCounter);
                    receiveLoss *= 100.0f;
                    // qDebug() << "LOSSCHANGED" << receiveLoss;
                    currLossCounter = 0;
                    currReceiveCounter = 0;
pixhawk's avatar
pixhawk committed
233
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
234 235
                }

236 237 238 239 240
                // 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
241 242 243 244 245 246 247 248 249 250 251 252 253
        }
    }
    receiveMutex.unlock();
}

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

254
/** @return System id of this application */
255
int MAVLinkProtocol::getSystemId()
256 257 258 259 260
{
    return MG::SYSTEM::ID;
}

/** @return Component id of this application */
261
int MAVLinkProtocol::getComponentId()
262 263 264 265
{
    return MG::SYSTEM::COMPID;
}

pixhawk's avatar
pixhawk committed
266 267 268 269 270 271 272 273 274 275 276 277 278
/**
 * @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;
    for (i = links.begin(); i != links.end(); ++i)
    {
        sendMessage(*i, message);
279
        //qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
280 281 282 283 284 285 286 287 288 289 290
    }
}

/**
 * @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
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
291 292
    // Rewriting header to ensure correct link ID is set
    if (link->getId() != 0) mavlink_finalize_message_chan(&message, this->getSystemId(), this->getComponentId(), link->getId(), message.len);
pixhawk's avatar
pixhawk committed
293
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
294
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312
    // If link is connected
    if (link->isConnected())
    {
        // Send the portion of the buffer now occupied by the message
        link->writeBytes((const char*)buffer, len);
    }
}

/**
 * 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()
{
    if (m_heartbeatsEnabled)
    {
        mavlink_message_t beat;
lm's avatar
lm committed
313
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
pixhawk's avatar
pixhawk committed
314 315 316 317 318 319 320 321 322 323 324
        sendMessage(beat);
    }
}

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

lm's avatar
lm committed
325 326
void MAVLinkProtocol::enableLogging(bool enabled)
{
327 328 329 330
    bool changed = false;
    if (enabled != m_loggingEnabled) changed = true;

    if (enabled)
lm's avatar
lm committed
331
    {
332 333 334 335 336 337 338 339 340 341
        if (m_logfile->isOpen())
        {
            m_logfile->flush();
            m_logfile->close();
        }
        if (!m_logfile->open(QIODevice::WriteOnly | QIODevice::Append))
        {
            emit protocolStatusMessage(tr("Opening MAVLink logfile for writing failed"), tr("MAVLink cannot log to the file %1, please choose a different file.").arg(m_logfile->fileName()));
            qDebug() << "OPENING LOGFILE FAILED!";
        }
lm's avatar
lm committed
342
    }
343
    else if (!enabled)
lm's avatar
lm committed
344
    {
345 346
        m_logfile->flush();
        m_logfile->close();
lm's avatar
lm committed
347 348
    }
    m_loggingEnabled = enabled;
349
    if (changed) emit loggingChanged(enabled);
350 351 352 353
}

void MAVLinkProtocol::setLogfileName(const QString& filename)
{
354
    m_logfile->flush();
355 356
    m_logfile->close();
    m_logfile->setFileName(filename);
357
    enableLogging(m_loggingEnabled);
lm's avatar
lm committed
358 359
}

lm's avatar
lm committed
360 361 362
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
    m_enable_version_check = enabled;
363
    emit versionCheckChanged(enabled);
lm's avatar
lm committed
364 365
}

pixhawk's avatar
pixhawk committed
366 367 368 369 370
bool MAVLinkProtocol::heartbeatsEnabled(void)
{
    return m_heartbeatsEnabled;
}

lm's avatar
lm committed
371 372 373 374 375
bool MAVLinkProtocol::loggingEnabled(void)
{
    return m_loggingEnabled;
}

lm's avatar
lm committed
376 377 378 379 380
bool MAVLinkProtocol::versionCheckEnabled(void)
{
    return m_enable_version_check;
}

pixhawk's avatar
pixhawk committed
381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
/**
 * 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;
}