Skip to content
Snippets Groups Projects
UAS.cc 103 KiB
Newer Older
  • Learn to ignore specific revisions
  • /*===================================================================
    
    pixhawk's avatar
    pixhawk committed
    ======================================================================*/
    
    /**
     * @file
     *   @brief Represents one unmanned aerial vehicle
     *
     *   @author Lorenz Meier <mavteam@student.ethz.ch>
     *
     */
    
    #include <QList>
    #include <QMessageBox>
    #include <QTimer>
    
    #include <QSettings>
    
    pixhawk's avatar
    pixhawk committed
    #include <iostream>
    #include <QDebug>
    #include <cmath>
    
    pixhawk's avatar
    pixhawk committed
    #include "UAS.h"
    #include "LinkInterface.h"
    #include "UASManager.h"
    
    #include "QGC.h"
    
    pixhawk's avatar
    pixhawk committed
    #include "GAudioOutput.h"
    
    #include "MAVLinkProtocol.h"
    
    pixhawk's avatar
    pixhawk committed
    #include "QGCMAVLink.h"
    
    #include "LinkManager.h"
    #include "SerialLink.h"
    
    pixhawk's avatar
    pixhawk committed
    
    
    #ifdef QGC_PROTOBUF_ENABLED
    #include <google/protobuf/descriptor.h>
    #endif
    
    
    /**
    * Gets the settings from the previous UAS (name, airframe, autopilot, battery specs)
    
    * by calling readSettings. This means the new UAS will have the same settings 
    * as the previous one created unless one calls deleteSettings in the code after
    * creating the UAS. 
    
    UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
    
    lm's avatar
    lm committed
        uasId(id),
        startTime(QGC::groundTimeMilliseconds()),
        commStatus(COMM_DISCONNECTED),
        name(""),
        autopilot(-1),
        links(new QList<LinkInterface*>()),
        unknownPackets(),
        mavlink(protocol),
        waypointManager(this),
        thrustSum(0),
        thrustMax(10),
    
        startVoltage(-1.0f),
        tickVoltage(10.5f),
        lastTickVoltageValue(13.0f),
        tickLowpassVoltage(12.0f),
    
    lm's avatar
    lm committed
        warnVoltage(9.5f),
        warnLevelPercent(20.0f),
    
    lm's avatar
    lm committed
        lpVoltage(12.0f),
        batteryRemainingEstimateEnabled(true),
        mode(-1),
        status(-1),
        navMode(-1),
        onboardTimeOffset(0),
        controlRollManual(true),
        controlPitchManual(true),
        controlYawManual(true),
        controlThrustManual(true),
        manualRollAngle(0),
        manualPitchAngle(0),
        manualYawAngle(0),
        manualThrust(0),
        receiveDropRate(0),
        sendDropRate(0),
        lowBattAlarm(false),
        positionLock(false),
        localX(0.0),
        localY(0.0),
        localZ(0.0),
        latitude(0.0),
        longitude(0.0),
        altitude(0.0),
        roll(0.0),
        pitch(0.0),
        yaw(0.0),
        statusTimeout(new QTimer(this)),
    
    LM's avatar
    LM committed
        #if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
    
        receivedObstacleListTimestamp(0.0),
        receivedPathTimestamp(0.0),
    
        receivedPointCloudTimestamp(0.0),
        receivedRGBDImageTimestamp(0.0),
    
    LM's avatar
    LM committed
        #endif
    
    lm's avatar
    lm committed
        paramsOnceRequested(false),
    
        airframe(QGC_AIRFRAME_GENERIC),
    
    lm's avatar
    lm committed
        attitudeKnown(false),
        paramManager(NULL),
        attitudeStamped(false),
        lastAttitude(0),
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        simulation(0),
    
    lm's avatar
    lm committed
        isLocalPositionKnown(false),
        isGlobalPositionKnown(false),
    
        systemIsArmed(false),
        nedPosGlobalOffset(0,0,0),
    
        nedAttGlobalOffset(0,0,0),
        connectionLost(false),
    
        lastVoltageWarning(0),
        lastNonNullTime(0),
    
        onboardTimeOffsetInvalidCount(0),
        hilEnabled(false)
    
    pixhawk's avatar
    pixhawk committed
    {
    
        for (unsigned int i = 0; i<255;++i)
        {
            componentID[i] = -1;
            componentMulti[i] = false;
        }
    
        color = UASInterface::getNextColor();
    
    lm's avatar
    lm committed
        setBatterySpecs(QString("9V,9.5V,12.6V"));
    
        connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
    
        connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
    
        statusTimeout->start(500);
    
        readSettings(); 
        type = MAV_TYPE_GENERIC;
    
        // Initial signals
        emit disarmed();
    
        emit armingChanged(false);  
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    /**
    * Saves the settings of name, airframe, autopilot type and battery specifications
    * by calling writeSettings.
    */
    
    pixhawk's avatar
    pixhawk committed
    UAS::~UAS()
    {
    
    pixhawk's avatar
    pixhawk committed
        delete links;
    
        delete statusTimeout;
        delete simulation;
    
    * Saves the settings of name, airframe, autopilot type and battery specifications
    * for the next instantiation of UAS.
    
    void UAS::writeSettings()
    {
        QSettings settings;
        settings.beginGroup(QString("MAV%1").arg(uasId));
        settings.setValue("NAME", this->name);
    
        settings.setValue("AIRFRAME", this->airframe);
        settings.setValue("AP_TYPE", this->autopilot);
    
        settings.setValue("BATTERY_SPECS", getBatterySpecs());
    
        settings.endGroup();
        settings.sync();
    }
    
    
    * Reads in the settings: name, airframe, autopilot type, and battery specifications
    * for the new UAS.
    */
    
    void UAS::readSettings()
    {
        QSettings settings;
        settings.beginGroup(QString("MAV%1").arg(uasId));
        this->name = settings.value("NAME", this->name).toString();
    
        this->airframe = settings.value("AIRFRAME", this->airframe).toInt();
        this->autopilot = settings.value("AP_TYPE", this->autopilot).toInt();
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        if (settings.contains("BATTERY_SPECS"))
        {
    
            setBatterySpecs(settings.value("BATTERY_SPECS").toString());
        }
    
    *  Deletes the settings origianally read into the UAS by readSettings.
    *  This is in case one does not want the old values but would rather 
    *  start with the values assigned by the constructor.
    */
    
    void UAS::deleteSettings()
    {
        this->name = "";
    
        this->airframe = QGC_AIRFRAME_GENERIC;
    
        setBatterySpecs(QString("9V,9.5V,12.6V"));
    
    /**
    * @ return the id of the uas
    
    pixhawk's avatar
    pixhawk committed
    {
        return uasId;
    }
    
    
    * Update the heartbeat.
    
        // Check if heartbeat timed out
        quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    
        if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
    
            connectionLost = true;
            QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
            GAudioOutput::instance()->say(audiostring.toLower());
        }
    
    
        // Update connection loss time on each iteration
        if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
        {
            connectionLossTime = heartbeatInterval;
    
            emit heartbeatTimeout(true, heartbeatInterval/1000);
    
        // Connection gained
        if (connectionLost && (heartbeatInterval < timeoutIntervalHeartbeat))
        {
            QString audiostring = QString("Link regained to system %1 after %2 seconds").arg(this->getUASID()).arg((int)(connectionLossTime/1000000));
            GAudioOutput::instance()->say(audiostring.toLower());
            connectionLost = false;
            connectionLossTime = 0;
    
        // Position lock is set by the MAVLink message handler
        // if no position lock is available, indicate an error
    
        if (positionLock)
        {
    
    lm's avatar
    lm committed
            if (((mode&MAV_MODE_FLAG_DECODE_POSITION_AUTO) || (mode&MAV_MODE_FLAG_DECODE_POSITION_GUIDED)) && positionLock)
    
                GAudioOutput::instance()->notifyNegative();
            }
        }
    
    Lorenz Meier's avatar
    Lorenz Meier committed
    
    //#define MAVLINK_OFFBOARD_CONTROL_MODE_NONE 0
    //#define MAVLINK_OFFBOARD_CONTROL_MODE_RATES 1
    //#define MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE 2
    //#define MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY 3
    //#define MAVLINK_OFFBOARD_CONTROL_MODE_POSITION 4
    //#define MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED 0x10
    
    //#warning THIS IS A HUGE HACK AND SHOULD NEVER SHOW UP IN ANY GIT REPOSITORY
    //    mavlink_message_t message;
    
    //            mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t sp;
    
    //            sp.group = 0;
    
    //            /* set rate mode, set zero rates and 20% throttle */
    //            sp.mode = MAVLINK_OFFBOARD_CONTROL_MODE_RATES | MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED;
    
    //            sp.roll[0] = INT16_MAX * 0.0f;
    //            sp.pitch[0] = INT16_MAX * 0.0f;
    //            sp.yaw[0] = INT16_MAX * 0.0f;
    //            sp.thrust[0] = UINT16_MAX * 0.3f;
    
    
    //            /* send from system 200 and component 0 */
    //            mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(200, 0, &message, &sp);
    
    //            sendMessage(message);
    
    * If the acitve UAS (the UAS that was selected) is not the one that is currently
    * active, then change the active UAS to the one that was selected.
    */
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setSelected()
    {
    
        if (UASManager::instance()->getActiveUAS() != this)
        {
    
            UASManager::instance()->setActiveUAS(this);
            emit systemSelected(true);
        }
    }
    
    
    * @return if the active UAS is the current UAS
    
    bool UAS::getSelected() const
    {
        return (UASManager::instance()->getActiveUAS() == this);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
    {
    
        if (!link) return;
    
    pixhawk's avatar
    pixhawk committed
            addLink(link);
    
            //        qDebug() << __FILE__ << __LINE__ << "ADDED LINK!" << link->getName();
    
    pixhawk's avatar
    pixhawk committed
        }
    
    
    LM's avatar
    LM committed
        if (!components.contains(message.compid))
        {
            QString componentName;
    
            switch (message.compid)
            {
            case MAV_COMP_ID_ALL:
    
    LM's avatar
    LM committed
            {
                componentName = "ANONYMOUS";
                break;
            }
    
    LM's avatar
    LM committed
            case MAV_COMP_ID_IMU:
    
    LM's avatar
    LM committed
            {
                componentName = "IMU #1";
                break;
            }
    
    LM's avatar
    LM committed
            case MAV_COMP_ID_CAMERA:
    
    LM's avatar
    LM committed
            {
                componentName = "CAMERA";
                break;
            }
    
    LM's avatar
    LM committed
            case MAV_COMP_ID_MISSIONPLANNER:
    
    LM's avatar
    LM committed
            {
                componentName = "MISSIONPLANNER";
                break;
            }
    
    LM's avatar
    LM committed
            }
    
            components.insert(message.compid, componentName);
            emit componentCreated(uasId, message.compid, componentName);
        }
    
    
        //    qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
    
    pixhawk's avatar
    pixhawk committed
    
    
    LM's avatar
    LM committed
        // Only accept messages from this system (condition 1)
        // and only then if a) attitudeStamped is disabled OR b) attitudeStamped is enabled
        // and we already got one attitude packet
        if (message.sysid == uasId && (!attitudeStamped || (attitudeStamped && (lastAttitude != 0)) || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
    
    pixhawk's avatar
    pixhawk committed
            QString uasState;
            QString stateDescription;
    
    pixhawk's avatar
    pixhawk committed
    
    
            bool multiComponentSourceDetected = false;
            bool wrongComponent = false;
    
    
            switch (message.compid)
            {
            case MAV_COMP_ID_IMU_2:
                // Prefer IMU 2 over IMU 1 (FIXME)
                componentID[message.msgid] = MAV_COMP_ID_IMU_2;
                break;
            default:
                // Do nothing
                break;
            }
    
    
            // Store component ID
            if (componentID[message.msgid] == -1)
            {
    
                // Prefer the first component
    
                componentID[message.msgid] = message.compid;
            }
            else
            {
                // Got this message already
                if (componentID[message.msgid] != message.compid)
                {
                    componentMulti[message.msgid] = true;
                    wrongComponent = true;
                }
            }
    
            if (componentMulti[message.msgid] == true) multiComponentSourceDetected = true;
    
    
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_HEARTBEAT:
    
    LM's avatar
    LM committed
                if (multiComponentSourceDetected && wrongComponent)
                {
                    break;
                }
    
                lastHeartbeat = QGC::groundTimeUsecs();
    
    pixhawk's avatar
    pixhawk committed
                emit heartbeat(this);
    
                mavlink_heartbeat_t state;
                mavlink_msg_heartbeat_decode(&message, &state);
    
    			
    			// Send the base_mode and system_status values to the plotter. This uses the ground time
    			// so the Ground Time checkbox must be ticked for these values to display
                quint64 time = getUnixTime();
    			QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid);
    
    			emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time);
    			emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time);
    			emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time);
    
    pixhawk's avatar
    pixhawk committed
                // Set new type if it has changed
    
                if (this->type != state.type)
    
                    this->type = state.type;
    
    lm's avatar
    lm committed
                        case MAV_TYPE_FIXED_WING:
    
                            setAirframe(UASInterface::QGC_AIRFRAME_EASYSTAR);
                            break;
    
    lm's avatar
    lm committed
                        case MAV_TYPE_QUADROTOR:
    
                            setAirframe(UASInterface::QGC_AIRFRAME_CHEETAH);
                            break;
    
                        case MAV_TYPE_HEXAROTOR:
                            setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
                            break;
    
                    this->autopilot = state.autopilot;
    
    pixhawk's avatar
    pixhawk committed
                    emit systemTypeSet(this, type);
                }
    
                bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
    
                if (systemIsArmed != currentlyArmed)
                {
                    systemIsArmed = currentlyArmed;
                    emit armingChanged(systemIsArmed);
                    if (systemIsArmed)
                    {
                        emit armed();
                    }
                    else
                    {
                        emit disarmed();
                    }
                }
    
                QString audiostring = QString("System %1").arg(uasId);
    
                QString stateAudio = "";
                QString modeAudio = "";
                QString navModeAudio = "";
                bool statechanged = false;
                bool modechanged = false;
    
    LM's avatar
    LM committed
    
    
                QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
    
    LM's avatar
    LM committed
    
    
    
                if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
    
                {
                    statechanged = true;
                    this->status = state.system_status;
                    getStatusForCode((int)state.system_status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
                    emit statusChanged(this->status);
    
                    shortStateText = uasState;
    
                    // Adjust for better audio
                    if (uasState == QString("STANDBY")) uasState = QString("standing by");
                    if (uasState == QString("EMERGENCY")) uasState = QString("emergency condition");
                    if (uasState == QString("CRITICAL")) uasState = QString("critical condition");
                    if (uasState == QString("SHUTDOWN")) uasState = QString("shutting down");
    
                    stateAudio = uasState;
    
    lm's avatar
    lm committed
    
    
                if (this->mode != static_cast<int>(state.base_mode))
    
                {
                    modechanged = true;
    
                    this->mode = static_cast<int>(state.base_mode);
    
                    shortModeText = getShortModeTextFor(this->mode);
    
                    emit modeChanged(this->getUASID(), shortModeText, "");
    
    LM's avatar
    LM committed
    
    
    LM's avatar
    LM committed
    
    
                if (navMode != state.custom_mode)
    
                    emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                    navMode = state.custom_mode;
    
    LM's avatar
    LM committed
                    //navModeAudio = tr(" changed nav mode to ") + tr("FIXME");
    
                // AUDIO
                if (modechanged && statechanged)
                {
                    // Output both messages
                    audiostring += modeAudio + " and " + stateAudio;
                }
                else if (modechanged || statechanged)
                {
                    // Output the one message
                    audiostring += modeAudio + stateAudio + navModeAudio;
                }
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY))
    
                    GAudioOutput::instance()->say(QString("emergency for system %1").arg(this->getUASID()));
                    QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
    
                }
                else if (modechanged || statechanged)
                {
                    GAudioOutput::instance()->stopEmergency();
    
                    GAudioOutput::instance()->say(audiostring.toLower());
    
    LM's avatar
    LM committed
            }
    
                break;
            case MAVLINK_MSG_ID_SYS_STATUS:
            {
    
    LM's avatar
    LM committed
                if (multiComponentSourceDetected && wrongComponent)
                {
                    break;
                }
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
    
    			// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
                quint64 time = getUnixTime();
    			QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
    			emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
    			emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
    			emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
    			emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
    			emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
    			emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
    
                emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
    
    LM's avatar
    LM committed
                emit loadChanged(this,state.load/10.0f);
    
    			emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
    
    LM's avatar
    LM committed
    
    
    			// Battery charge/time remaining/voltage calculations
    
    LM's avatar
    LM committed
                currentVoltage = state.voltage_battery/1000.0f;
                lpVoltage = filterVoltage(currentVoltage);
    
                tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
    
    LM's avatar
    LM committed
    
    
                // We don't want to tick above the threshold
                if (tickLowpassVoltage > tickVoltage)
                {
                    lastTickVoltageValue = tickLowpassVoltage;
                }
    
                if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
    
                        /* warn if lower than treshold */
                        && (lpVoltage < tickVoltage)
                        /* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
                        && (currentVoltage > 3.3f)
                        /* warn only if current voltage is really still lower by a reasonable amount */
    
                        && ((currentVoltage - 0.2f) < tickVoltage)
    
                        /* warn only every 12 seconds */
                        && (QGC::groundTimeUsecs() - lastVoltageWarning) > 12000000)
    
                    GAudioOutput::instance()->say(QString("voltage warning: %1 volts").arg(lpVoltage, 0, 'f', 1, QChar(' ')));
                    lastVoltageWarning = QGC::groundTimeUsecs();
    
                    lastTickVoltageValue = tickLowpassVoltage;
                }
    
                if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
    
    LM's avatar
    LM committed
                timeRemaining = calculateTimeRemaining();
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
                {
                    chargeLevel = state.battery_remaining;
                }
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
    
    			emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
                emit voltageChanged(message.sysid, currentVoltage);
    			emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
    
    			// And if the battery current draw is measured, log that also.
    			if (state.current_battery != -1)
    			{
    				emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time);
    			}
    
    LM's avatar
    LM committed
                // LOW BATTERY ALARM
    
                if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3))
    
    LM's avatar
    LM committed
                {
                    startLowBattAlarm();
    
    LM's avatar
    LM committed
                else
    
    LM's avatar
    LM committed
                {
    
    LM's avatar
    LM committed
                    stopLowBattAlarm();
    
    pixhawk's avatar
    pixhawk committed
                }
    
                // control_sensors_enabled:
                // relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
                emit attitudeControlEnabled(state.onboard_control_sensors_enabled & (1 << 11));
                emit positionYawControlEnabled(state.onboard_control_sensors_enabled & (1 << 12));
                emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13));
                emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14));
    
    
    			// Trigger drop rate updates as needed. Here we convert the incoming
    			// drop_rate_comm value from 1/100 of a percent in a uint16 to a true
    			// percentage as a float. We also cap the incoming value at 100% as defined
    			// by the MAVLink specifications.
    			if (state.drop_rate_comm > 10000)
    			{
    
    			emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
    			emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
    
    LM's avatar
    LM committed
                break;
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_ATTITUDE:
    
    LM's avatar
    LM committed
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
    
    LM's avatar
    LM committed
                emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
    
    
                if (!wrongComponent)
                {
                    lastAttitude = time;
                    roll = QGC::limitAngleToPMPIf(attitude.roll);
                    pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                    yaw = QGC::limitAngleToPMPIf(attitude.yaw);
    
                    //                // Emit in angles
    
                    //                // Convert yaw angle to compass value
                    //                // in 0 - 360 deg range
                    //                float compass = (yaw/M_PI)*180.0+360.0f;
                    //                if (compass > -10000 && compass < 10000)
                    //                {
                    //                    while (compass > 360.0f) {
                    //                        compass -= 360.0f;
                    //                    }
                    //                }
                    //                else
                    //                {
                    //                    // Set to 0, since it is an invalid value
                    //                    compass = 0.0f;
                    //                }
    
                    attitudeKnown = true;
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                    emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
                }
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET:
            {
                mavlink_local_position_ned_system_global_offset_t offset;
                mavlink_msg_local_position_ned_system_global_offset_decode(&message, &offset);
                nedPosGlobalOffset.setX(offset.x);
                nedPosGlobalOffset.setY(offset.y);
                nedPosGlobalOffset.setZ(offset.z);
                nedAttGlobalOffset.setX(offset.roll);
                nedAttGlobalOffset.setY(offset.pitch);
                nedAttGlobalOffset.setZ(offset.yaw);
            }
                break;
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_HIL_CONTROLS:
    
    LM's avatar
    LM committed
            {
                mavlink_hil_controls_t hil;
                mavlink_msg_hil_controls_decode(&message, &hil);
                emit hilControlsChanged(hil.time_usec, hil.roll_ailerons, hil.pitch_elevator, hil.yaw_rudder, hil.throttle, hil.mode, hil.nav_mode);
            }
    
    lm's avatar
    lm committed
                break;
    
    LM's avatar
    LM committed
            {
                mavlink_vfr_hud_t hud;
                mavlink_msg_vfr_hud_decode(&message, &hud);
                quint64 time = getUnixTime();
                // Display updated values
                emit thrustChanged(this, hud.throttle/100.0);
    
    LM's avatar
    LM committed
                if (!attitudeKnown)
                {
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
    
    LM's avatar
    LM committed
                }
    
    LM's avatar
    LM committed
    
                emit altitudeChanged(uasId, hud.alt);
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
            }
    
    LM's avatar
    LM committed
                break;
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
    
    lm's avatar
    lm committed
                //std::cerr << std::endl;
    
    pixhawk's avatar
    pixhawk committed
                //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
    
    LM's avatar
    LM committed
            {
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
                quint64 time = getUnixTime(pos.time_boot_ms);
    
    LM's avatar
    LM committed
    
    
    LM's avatar
    LM committed
                // Emit position always with component ID
    
    LM's avatar
    LM committed
                emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
    
    LM's avatar
    LM committed
                if (!wrongComponent)
                {
                    localX = pos.x;
                    localY = pos.y;
                    localZ = pos.z;
    
    LM's avatar
    LM committed
                    // Emit
    
    LM's avatar
    LM committed
                    emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                    emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
    
    LM's avatar
    LM committed
                    // Set internal state
                    if (!positionLock) {
                        // If position was not locked before, notify positive
                        GAudioOutput::instance()->notifyPositive();
    
    LM's avatar
    LM committed
                    }
    
    LM's avatar
    LM committed
                    positionLock = true;
                    isLocalPositionKnown = true;
    
    LM's avatar
    LM committed
            }
    
                break;
            case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
    
    LM's avatar
    LM committed
            {
                mavlink_global_vision_position_estimate_t pos;
                mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
                emit localPositionChanged(this, message.compid, pos.x, pos.y, pos.z, time);
                emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
    
                //std::cerr << std::endl;
                //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
    
    LM's avatar
    LM committed
            {
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
                quint64 time = getUnixTime();
                latitude = pos.lat/(double)1E7;
                longitude = pos.lon/(double)1E7;
                altitude = pos.alt/1000.0;
                speedX = pos.vx/100.0;
                speedY = pos.vy/100.0;
                speedZ = pos.vz/100.0;
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
    
    LM's avatar
    LM committed
                // Set internal state
                if (!positionLock)
    
    LM's avatar
    LM committed
                {
    
    LM's avatar
    LM committed
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
                isGlobalPositionKnown = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
            }
                break;
            case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);
    
                // SANITY CHECK
                // only accept values in a realistic range
                // quint64 time = getUnixTime(pos.time_usec);
                quint64 time = getUnixTime(pos.time_usec);
    
                
                emit gpsLocalizationChanged(this, pos.fix_type);
                // TODO: track localization state not only for gps but also for other loc. sources
                int loc_type = pos.fix_type;
                if (loc_type == 1)
                {
                    loc_type = 0; 
                }
                emit localizationChanged(this, loc_type);
    
    LM's avatar
    LM committed
    
                if (pos.fix_type > 2)
    
    LM's avatar
    LM committed
                {
    
    LM's avatar
    LM committed
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
    
    LM's avatar
    LM committed
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;
    
                    isGlobalPositionKnown = true;
    
    LM's avatar
    LM committed
    
    
    LM's avatar
    LM committed
                    // Check for NaN
                    int alt = pos.alt;
                    if (!isnan(alt) && !isinf(alt))
    
    LM's avatar
    LM committed
                        alt = 0;
                        //emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN or Inf FOR ALTITUDE");
                    }
                    // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
                    // Smaller than threshold and not NaN
    
    LM's avatar
    LM committed
    
    
    LM's avatar
    LM committed
                    float vel = pos.vel/100.0f;
    
    LM's avatar
    LM committed
    
    
    LM's avatar
    LM committed
                    if (vel < 1000000 && !isnan(vel) && !isinf(vel))
                    {
                        // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time);
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    }
                    else
                    {
                        emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
    
    lm's avatar
    lm committed
                    }
                }
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;
    
    LM's avatar
    LM committed
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
                for(int i = 0; i < (int)pos.satellites_visible; i++)
    
    LM's avatar
    LM committed
                    emit gpsSatelliteStatusChanged(uasId, (unsigned char)pos.satellite_prn[i], (unsigned char)pos.satellite_elevation[i], (unsigned char)pos.satellite_azimuth[i], (unsigned char)pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i]));
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
    
    LM's avatar
    LM committed
            {
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
    
                emit homePositionChanged(uasId, pos.latitude / 10000000.0, pos.longitude / 10000000.0, pos.altitude / 1000.0);
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
    
    LM's avatar
    LM committed
            {
                mavlink_rc_channels_raw_t channels;
                mavlink_msg_rc_channels_raw_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelRawChanged(0, channels.chan1_raw);
                emit remoteControlChannelRawChanged(1, channels.chan2_raw);
                emit remoteControlChannelRawChanged(2, channels.chan3_raw);
                emit remoteControlChannelRawChanged(3, channels.chan4_raw);
                emit remoteControlChannelRawChanged(4, channels.chan5_raw);
                emit remoteControlChannelRawChanged(5, channels.chan6_raw);
                emit remoteControlChannelRawChanged(6, channels.chan7_raw);
                emit remoteControlChannelRawChanged(7, channels.chan8_raw);
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
    
    LM's avatar
    LM committed
            {
                mavlink_rc_channels_scaled_t channels;
                mavlink_msg_rc_channels_scaled_decode(&message, &channels);
                emit remoteControlRSSIChanged(channels.rssi/255.0f);
                emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
                emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
            }
    
    LM's avatar
    LM committed
                break;
    
    LM's avatar
    LM committed
            {
                mavlink_param_value_t value;
                mavlink_msg_param_value_decode(&message, &value);
                QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
    
                // Construct a string stopping at the first NUL (0) character, else copy the whole
                // byte array (max MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN, so safe)
                QString parameterName(bytes);
    
    LM's avatar
    LM committed
                int component = message.compid;
                mavlink_param_union_t val;
                val.param_float = value.param_value;
                val.type = value.param_type;
    
                // Insert component if necessary
                if (!parameters.contains(component))
    
    LM's avatar
    LM committed
                    parameters.insert(component, new QMap<QString, QVariant>());
                }
    
    LM's avatar
    LM committed
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
    
    LM's avatar
    LM committed
                // Insert with correct type
                switch (value.param_type)
                {
    
                case MAV_PARAM_TYPE_REAL32:
    
    LM's avatar
    LM committed
                {
                    // Variant
                    QVariant param(val.param_float);
                    parameters.value(component)->insert(parameterName, param);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
    
    //                qDebug() << "RECEIVED PARAM:" << param;
    
    LM's avatar
    LM committed
                }
    
    LM's avatar
    LM committed
                    break;
    
                case MAV_PARAM_TYPE_UINT32:
    
    LM's avatar
    LM committed
                {
                    // Variant
                    QVariant param(val.param_uint32);
                    parameters.value(component)->insert(parameterName, param);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
    
    //                qDebug() << "RECEIVED PARAM:" << param;
    
    LM's avatar
    LM committed
                }
    
    LM's avatar
    LM committed
                    break;
    
                case MAV_PARAM_TYPE_INT32:
    
    LM's avatar
    LM committed
                {
                    // Variant
                    QVariant param(val.param_int32);
                    parameters.value(component)->insert(parameterName, param);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, param);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
    
    //                qDebug() << "RECEIVED PARAM:" << param;
    
    LM's avatar
    LM committed
                }
                    break;
                default:
                    qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << value.param_type;
                }
            }
    
    LM's avatar
    LM committed
                break;
    
            case MAVLINK_MSG_ID_COMMAND_ACK:
    
                mavlink_command_ack_t ack;
                mavlink_msg_command_ack_decode(&message, &ack);
    
                switch (ack.result)
                {
                case MAV_RESULT_ACCEPTED:
    
                    emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
    
                    break;
                case MAV_RESULT_TEMPORARILY_REJECTED:
    
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Temporarily rejected CMD: %1").arg(ack.command));
    
                    break;
                case MAV_RESULT_DENIED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Denied CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_UNSUPPORTED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Unsupported CMD: %1").arg(ack.command));
                }
                    break;
                case MAV_RESULT_FAILED:
                {
                    emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Failed CMD: %1").arg(ack.command));
                }
                    break;
                }
            }
    
    LM's avatar
    LM committed
            case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
    
    LM's avatar
    LM committed
            {
                mavlink_roll_pitch_yaw_thrust_setpoint_t out;
                mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
            }
    
    LM's avatar
    LM committed
                break;
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_MISSION_COUNT:
    
    LM's avatar
    LM committed
            {
                mavlink_mission_count_t wpc;
                mavlink_msg_mission_count_decode(&message, &wpc);
    
                if(wpc.target_system == mavlink->getSystemId() || wpc.target_system == 0)
    
    LM's avatar
    LM committed
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
    
    pixhawk's avatar
    pixhawk committed
                }
    
    LM's avatar
    LM committed
                else
                {
    
                    qDebug() << "Got waypoint message, but was wrong system id" << wpc.target_system;
    
    LM's avatar
    LM committed
                break;
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_MISSION_ITEM:
    
    LM's avatar
    LM committed
            {
                mavlink_mission_item_t wp;
                mavlink_msg_mission_item_decode(&message, &wp);
                //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
    
                if(wp.target_system == mavlink->getSystemId() || wp.target_system == 0)
    
    LM's avatar
    LM committed
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
                else
                {
    
                    qDebug() << "Got waypoint message, but was wrong system id" << wp.target_system;
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_MISSION_ACK:
    
    LM's avatar
    LM committed
            {
                mavlink_mission_ack_t wpa;
                mavlink_msg_mission_ack_decode(&message, &wpa);
    
                if((wpa.target_system == mavlink->getSystemId() || wpa.target_system == 0) &&
                        (wpa.target_component == mavlink->getComponentId() || wpa.target_component == 0))
    
    LM's avatar
    LM committed
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
    
    LM's avatar
    LM committed
            }
    
    LM's avatar
    LM committed
                break;