Skip to content
MAVLinkProtocol.cc 14.2 KiB
Newer Older
pixhawk's avatar
pixhawk committed
/*=====================================================================

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

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

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

pixhawk's avatar
pixhawk committed
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
    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
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
    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
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed

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

/**
 * @file
pixhawk's avatar
pixhawk committed
 *   @brief Implementation of class MAVLinkProtocol
 *   @author Lorenz Meier <mail@qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
 */

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

#include <QDebug>
#include <QTime>
lm's avatar
lm committed
#include <QApplication>
pixhawk's avatar
pixhawk committed

#include "MG.h"
#include "MAVLinkProtocol.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "UASInterface.h"
#include "UAS.h"
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
#include "ArduPilotMegaMAV.h"
pixhawk's avatar
pixhawk committed
#include "configuration.h"
#include "LinkManager.h"
pixhawk's avatar
pixhawk committed
#include <QGCMAVLink.h>
pixhawk's avatar
pixhawk committed
#include "QGC.h"
pixhawk's avatar
pixhawk committed

/**
 * 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
        m_heartbeatsEnabled(false),
        m_loggingEnabled(false),
        m_logfile(NULL)
pixhawk's avatar
pixhawk committed
{
    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
    totalReceiveCounter = 0;
    totalLossCounter = 0;
    currReceiveCounter = 0;
    currLossCounter = 0;
lm's avatar
lm committed
    for (int i = 0; i < 256; i++)
    {
        for (int j = 0; j < 256; j++)
        {
            lastIndex[i][j] = -1;
        }
    }
pixhawk's avatar
pixhawk committed
}

MAVLinkProtocol::~MAVLinkProtocol()
{
pixhawk's avatar
pixhawk committed
    if (m_logfile)
    {
        m_logfile->close();
        delete m_logfile;
    }
pixhawk's avatar
pixhawk committed
}



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

pixhawk's avatar
pixhawk committed
}

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

pixhawk's avatar
pixhawk committed
/**
 * 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
 **/
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
pixhawk's avatar
pixhawk committed
{
    receiveMutex.lock();
    mavlink_message_t message;
    mavlink_status_t status;
    for (int position = 0; position < b.size(); position++)
pixhawk's avatar
pixhawk committed
    {
        unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
pixhawk's avatar
pixhawk committed

        if (decodeState == 1)
        {
pixhawk's avatar
pixhawk committed
            // Log data
            if (m_loggingEnabled)
            {
                uint8_t buf[MAVLINK_MAX_PACKET_LEN];
pixhawk's avatar
pixhawk committed
                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
                m_logfile->write((const char*) buf);
                qDebug() << "WROTE LOGFILE";
            }

pixhawk's avatar
pixhawk committed
            // 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
            if (uas == NULL && message.msgid == MAVLINK_MSG_ID_HEARTBEAT)
pixhawk's avatar
pixhawk committed
            {
                // 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.

                // FIXME Current debugging
                // check if the UAS has the same id like this system
                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;
                }

                // 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
                // First create new UAS object
                // Decode heartbeat message
                mavlink_heartbeat_t heartbeat;
                mavlink_msg_heartbeat_decode(&message, &heartbeat);
                switch (heartbeat.autopilot)
                {
                case MAV_AUTOPILOT_GENERIC:
                    uas = new UAS(this, message.sysid);
                    // Connect this robot to the UAS object
                    connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), uas, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
                    break;
                case MAV_AUTOPILOT_PIXHAWK:
                    // Fixme differentiate between quadrotor and coaxial here
                    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;
                }
                    {
                    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;
                }
                case MAV_AUTOPILOT_ARDUPILOTMEGA:
                    ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(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;
                }
                    break;
                default:
                    uas = new UAS(this, message.sysid);
                    break;
                }
pixhawk's avatar
pixhawk committed
                // Make UAS aware that this link can be used to communicate with the actual robot
                uas->addLink(link);
                // Now add UAS to "official" list, which makes the whole application aware of it
                UASManager::instance()->addUAS(uas);
            }

            // Only count message if UAS exists for this message
            if (uas != NULL)
lm's avatar
lm committed
            {
                // Increase receive counter
                totalReceiveCounter++;
                currReceiveCounter++;
                qint64 lastLoss = totalLossCounter;
                // Update last packet index
                if (lastIndex[message.sysid][message.compid] == -1)
lm's avatar
lm committed
                {
                    lastIndex[message.sysid][message.compid] = message.seq;
lm's avatar
lm committed
                }
                else
lm's avatar
lm committed
                {
lm's avatar
lm committed
                    if (lastIndex[message.sysid][message.compid] == 255)
                    {
                        lastIndex[message.sysid][message.compid] = 0;
                    }
                    else
                    {
                        lastIndex[message.sysid][message.compid]++;
                    }

                    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
                if (lastLoss != totalLossCounter || (totalReceiveCounter % 64 == 0))
                {
                    // 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
                    emit receiveLossChanged(message.sysid, receiveLoss);
lm's avatar
lm committed
                }

                // 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
        }
    }
    receiveMutex.unlock();
}

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

/** @return System id of this application */
int MAVLinkProtocol::getSystemId()
{
    return MG::SYSTEM::ID;
}

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

pixhawk's avatar
pixhawk committed
/**
 * @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);
        //qDebug() << __FILE__ << __LINE__ << "SENT MESSAGE OVER" << ((LinkInterface*)*i)->getName() << "LIST SIZE:" << links.size();
pixhawk's avatar
pixhawk committed
    }
}

/**
 * @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];
    // 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
    // Write message into buffer, prepending start sign
pixhawk's avatar
pixhawk committed
    int len = mavlink_msg_to_send_buffer(buffer, &message);
pixhawk's avatar
pixhawk committed
    // 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;
        mavlink_msg_heartbeat_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID,&beat, OCU, MAV_AUTOPILOT_GENERIC);
pixhawk's avatar
pixhawk committed
        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
void MAVLinkProtocol::enableLogging(bool enabled)
{
    if (enabled && !m_loggingEnabled)
    {
pixhawk's avatar
pixhawk committed
       m_logfile = new QFile(getLogfileName());
       m_logfile->open(QIODevice::WriteOnly | QIODevice::Append);
lm's avatar
lm committed
    }
    else
    {
       m_logfile->close();
       delete m_logfile;
       m_logfile = NULL;
    }
    m_loggingEnabled = enabled;
}

pixhawk's avatar
pixhawk committed
bool MAVLinkProtocol::heartbeatsEnabled(void)
{
    return m_heartbeatsEnabled;
}

lm's avatar
lm committed
bool MAVLinkProtocol::loggingEnabled(void)
{
    return m_loggingEnabled;
}

pixhawk's avatar
pixhawk committed
/**
 * 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;
}