MAVLinkProtocol.cc 15.2 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

pixhawk's avatar
pixhawk committed
3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

pixhawk's avatar
pixhawk committed
5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

pixhawk's avatar
pixhawk committed
7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

pixhawk's avatar
pixhawk committed
9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

pixhawk's avatar
pixhawk committed
14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
pixhawk's avatar
pixhawk committed
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25

======================================================================*/

/**
 * @file
pixhawk's avatar
pixhawk committed
26 27
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
28 29 30 31 32 33 34
 */

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

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
35
#include <QApplication>
pixhawk's avatar
pixhawk committed
36
#include <QMessageBox>
pixhawk's avatar
pixhawk committed
37 38 39 40 41 42 43

#include "MG.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
44 45
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
46
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
47 48
#include "configuration.h"
#include "LinkManager.h"
pixhawk's avatar
pixhawk committed
49
#include "MainWindow.h"
pixhawk's avatar
pixhawk committed
50
#include <QGCMAVLink.h>
51
#include "QGC.h"
pixhawk's avatar
pixhawk committed
52 53 54 55 56 57 58 59

/**
 * 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
60 61 62
        m_heartbeatsEnabled(false),
        m_loggingEnabled(false),
        m_logfile(NULL)
pixhawk's avatar
pixhawk committed
63 64 65 66 67
{
    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
68 69
    totalReceiveCounter = 0;
    totalLossCounter = 0;
70 71
    currReceiveCounter = 0;
    currLossCounter = 0;
lm's avatar
lm committed
72 73 74 75 76 77 78
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
            lastIndex[i][j] = -1;
        }
    }
pixhawk's avatar
pixhawk committed
79 80 81 82
}

MAVLinkProtocol::~MAVLinkProtocol()
{
pixhawk's avatar
pixhawk committed
83 84 85 86 87
    if (m_logfile)
    {
        m_logfile->close();
        delete m_logfile;
    }
pixhawk's avatar
pixhawk committed
88 89 90 91 92 93
}



void MAVLinkProtocol::run()
{
lm's avatar
lm committed
94

pixhawk's avatar
pixhawk committed
95 96
}

pixhawk's avatar
pixhawk committed
97 98 99 100 101
QString MAVLinkProtocol::getLogfileName()
{
    return QCoreApplication::applicationDirPath()+"/mavlink.log";
}

pixhawk's avatar
pixhawk committed
102 103 104 105 106 107 108 109
/**
 * 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
 **/
110
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
111 112 113 114
{
    receiveMutex.lock();
    mavlink_message_t message;
    mavlink_status_t status;
115
    for (int position = 0; position < b.size(); position++)
pixhawk's avatar
pixhawk committed
116
    {
117
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed
118 119 120

        if (decodeState == 1)
        {
pixhawk's avatar
pixhawk committed
121 122 123 124
            // Log data
            if (m_loggingEnabled)
            {
                uint8_t buf[MAVLINK_MAX_PACKET_LEN];
125 126 127
                quint64 time = MG::TIME::getGroundTimeNowUsecs();
                memcpy(buf, (void*)&time, sizeof(quint64));
                mavlink_msg_to_send_buffer(buf+sizeof(quint64), &message);
pixhawk's avatar
pixhawk committed
128 129 130 131
                m_logfile->write((const char*) buf);
                qDebug() << "WROTE LOGFILE";
            }

pixhawk's avatar
pixhawk committed
132 133 134 135 136 137
            // 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
138
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
pixhawk's avatar
pixhawk committed
139 140 141 142 143 144 145
            {
                // 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
146
                // Check if the UAS has the same id like this system
147 148 149 150 151
                if (message.sysid == getSystemId())
                {
                    qDebug() << "WARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\n\n RECEIVED MESSAGE FROM THIS SYSTEM WITH ID" << message.msgid << "FROM COMPONENT" << message.compid;
                }

152 153 154 155
                // 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
156
                // First create new UAS object
157 158
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
pixhawk's avatar
pixhawk committed
159 160
                // Reset version field to 0
                heartbeat.mavlink_version = 0;
161
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
pixhawk's avatar
pixhawk committed
162 163 164 165 166

                // Check if the UAS has a different protocol version
                if (heartbeat.mavlink_version != MAVLINK_VERSION)
                {
                    // Bring up dialog to inform user
167 168 169
                    MainWindow::instance()->showCriticalMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
                                                                 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));

pixhawk's avatar
pixhawk committed
170 171 172 173 174

                    // Ignore this message and continue gracefully
                    continue;
                }

175 176 177
                switch (heartbeat.autopilot)
                {
                case MAV_AUTOPILOT_GENERIC:
178

179
                    uas = new UAS(this, message.sysid);
180

181 182
                    // Connect this robot to the UAS object
                    connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), uas, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
183 184
                    break;
                case MAV_AUTOPILOT_PIXHAWK:
185
                    {
186
                    // Fixme differentiate between quadrotor and coaxial here
187 188 189 190 191 192 193 194
                    PxQuadMAV* mav = new PxQuadMAV(this, message.sysid);
                    // Connect this robot to the UAS object
                    // it is IMPORTANT here to use the right object type,
                    // else the slot of the parent object is called (and thus the special
                    // packets never reach their goal)
                    connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
                    uas = mav;
                }
195 196
                    break;
                case MAV_AUTOPILOT_SLUGS:
197 198 199 200 201 202 203 204 205
                    {
                    SlugsMAV* mav = new SlugsMAV(this, message.sysid);
                    // Connect this robot to the UAS object
                    // it is IMPORTANT here to use the right object type,
                    // else the slot of the parent object is called (and thus the special
                    // packets never reach their goal)
                    connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
                    uas = mav;
                }
206
                    break;
207
                case MAV_AUTOPILOT_ARDUPILOTMEGA:
208
                    {
209
                    ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(this, message.sysid);
210 211 212 213 214 215 216
                    // Connect this robot to the UAS object
                    // it is IMPORTANT here to use the right object type,
                    // else the slot of the parent object is called (and thus the special
                    // packets never reach their goal)
                    connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
                    uas = mav;
                }
217 218 219 220 221
                    break;
                default:
                    uas = new UAS(this, message.sysid);
                    break;
                }
222

223 224
                // Set the autopilot type
                uas->setAutopilotType((int)heartbeat.autopilot);
225

pixhawk's avatar
pixhawk committed
226 227
                // Make UAS aware that this link can be used to communicate with the actual robot
                uas->addLink(link);
228

pixhawk's avatar
pixhawk committed
229 230
                // Now add UAS to "official" list, which makes the whole application aware of it
                UASManager::instance()->addUAS(uas);
231

pixhawk's avatar
pixhawk committed
232
            }
233 234 235

            // Only count message if UAS exists for this message
            if (uas != NULL)
lm's avatar
lm committed
236
            {
237 238 239 240 241 242
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
                if (lastIndex[message.sysid][message.compid] == -1)
lm's avatar
lm committed
243
                {
244
                    lastIndex[message.sysid][message.compid] = message.seq;
lm's avatar
lm committed
245 246
                }
                else
lm's avatar
lm committed
247
                {
lm's avatar
lm committed
248 249 250 251 252 253 254 255
                    if (lastIndex[message.sysid][message.compid] == 255)
                    {
                        lastIndex[message.sysid][message.compid] = 0;
                    }
                    else
                    {
                        lastIndex[message.sysid][message.compid]++;
                    }
256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282

                    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
283
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0))
284 285 286 287 288 289 290 291
                {
                    // 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
292
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
293 294
                }

295 296 297 298 299
                // 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
300 301 302 303 304 305 306 307 308 309 310 311 312
        }
    }
    receiveMutex.unlock();
}

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

313
/** @return System id of this application */
314
int MAVLinkProtocol::getSystemId()
315 316 317 318 319
{
    return MG::SYSTEM::ID;
}

/** @return Component id of this application */
320
int MAVLinkProtocol::getComponentId()
321 322 323 324
{
    return MG::SYSTEM::COMPID;
}

pixhawk's avatar
pixhawk committed
325 326 327 328 329 330 331 332 333 334 335 336 337
/**
 * @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);
338
        //qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
339 340 341 342 343 344 345 346 347 348 349
    }
}

/**
 * @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];
350 351
    // 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
352
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
353
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371
    // 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
372
        mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, OCU, MAV_AUTOPILOT_GENERIC);
pixhawk's avatar
pixhawk committed
373 374 375 376 377 378 379 380 381 382 383
        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
384 385 386 387
void MAVLinkProtocol::enableLogging(bool enabled)
{
    if (enabled && !m_loggingEnabled)
    {
pixhawk's avatar
pixhawk committed
388 389
       m_logfile = new QFile(getLogfileName());
       m_logfile->open(QIODevice::WriteOnly | QIODevice::Append);
lm's avatar
lm committed
390 391 392 393 394 395 396 397 398 399
    }
    else
    {
       m_logfile->close();
       delete m_logfile;
       m_logfile = NULL;
    }
    m_loggingEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
400 401 402 403 404
bool MAVLinkProtocol::heartbeatsEnabled(void)
{
    return m_heartbeatsEnabled;
}

lm's avatar
lm committed
405 406 407 408 409
bool MAVLinkProtocol::loggingEnabled(void)
{
    return m_loggingEnabled;
}

pixhawk's avatar
pixhawk committed
410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425
/**
 * 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;
}