Skip to content
UAS.cc 90.2 KiB
Newer Older
/*===================================================================
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

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(0),
warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
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)),
paramsOnceRequested(false),
airframe(0),
attitudeKnown(false),
LM's avatar
LM committed
paramManager(NULL),
LM's avatar
LM committed
attitudeStamped(false),
lm's avatar
lm committed
lastAttitude(0),
    simulation(new QGCFlightGearLink(this))
pixhawk's avatar
pixhawk committed
{
    color = UASInterface::getNextColor();
pixhawk's avatar
pixhawk committed
    setBattery(LIPOLY, 3);
    connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
    connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
    statusTimeout->start(500);
pixhawk's avatar
pixhawk committed
}

UAS::~UAS()
{
pixhawk's avatar
pixhawk committed
    delete links;
pixhawk's avatar
pixhawk committed
}

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();
}

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();
    if (settings.contains("BATTERY_SPECS")) {
        setBatterySpecs(settings.value("BATTERY_SPECS").toString());
    }
pixhawk's avatar
pixhawk committed
{
    return uasId;
}

    // Check if heartbeat timed out
    quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
    if (heartbeatInterval > timeoutIntervalHeartbeat)
    {
        emit heartbeatTimeout(heartbeatInterval);
        emit heartbeatTimeout();
    }

    // Position lock is set by the MAVLink message handler
    // if no position lock is available, indicate an error
    if (positionLock)
    {
    }
    else
    {
        if ((mode == (int)MAV_MODE_AUTO || mode == (int)MAV_MODE_GUIDED) && positionLock)
        {
pixhawk's avatar
pixhawk committed
void UAS::setSelected()
{
    if (UASManager::instance()->getActiveUAS() != this) {
        UASManager::instance()->setActiveUAS(this);
        emit systemSelected(true);
    }
}

bool UAS::getSelected() const
{
    return (UASManager::instance()->getActiveUAS() == this);
pixhawk's avatar
pixhawk committed
}

void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_FLOAT)
    {
pixhawk's avatar
pixhawk committed
        mavlink_named_value_float_t val;
        mavlink_msg_named_value_float_decode(&message, &val);
lm's avatar
lm committed
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
    }
    else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
    {
pixhawk's avatar
pixhawk committed
        mavlink_named_value_int_t val;
        mavlink_msg_named_value_int_decode(&message, &val);
lm's avatar
lm committed
        QByteArray bytes(val.name, MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN);
        emit valueChanged(this->getUASID(), QString(bytes), tr("raw"), val.value, getUnixTime());
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
    }
    //    else
    //    {
    //        qDebug() << __FILE__ << __LINE__ << "DID NOT ADD LINK" << link->getName() << "ALREADY IN LIST";
    //    }
pixhawk's avatar
pixhawk committed

    //    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

pixhawk's avatar
pixhawk committed
        case MAVLINK_MSG_ID_HEARTBEAT:
            lastHeartbeat = QGC::groundTimeUsecs();
pixhawk's avatar
pixhawk committed
            emit heartbeat(this);
            mavlink_heartbeat_t state;
            mavlink_msg_heartbeat_decode(&message, &state);
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;
                    default:
                        // Do nothing
                        break;
                    }
                }
                this->autopilot = state.autopilot;
pixhawk's avatar
pixhawk committed
                emit systemTypeSet(this, type);
            }
            QString audiostring = "System " + getUASName();
            QString stateAudio = "";
            QString modeAudio = "";
            QString navModeAudio = "";
            bool statechanged = false;
            bool modechanged = false;
            if (state.system_status != this->status)
            {
                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;
                stateAudio = tr(" changed status to ") + 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);
pixhawk's avatar
pixhawk committed

                shortModeText = getShortModeTextFor(this->mode);
                emit modeChanged(this->getUASID(), shortModeText, "");
LM's avatar
LM committed

                modeAudio = " is now in " + shortModeText;
            }
LM's avatar
LM committed

            if (navMode != state.custom_mode)
                emit navModeChanged(uasId, state.custom_mode, getNavModeText(state.custom_mode));
                navMode = state.custom_mode;
                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;
            }
            if ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)
            {
                GAudioOutput::instance()->startEmergency();
            }
            else if (modechanged || statechanged)
            {
                GAudioOutput::instance()->stopEmergency();
                GAudioOutput::instance()->say(audiostring.toLower());
lm's avatar
lm committed

            if (state.system_status == MAV_STATE_POWEROFF)
            {
                emit systemRemoved(this);
                emit systemRemoved();
            }
}
            break;
        case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
        case MAVLINK_MSG_ID_NAMED_VALUE_INT:
            // Receive named value message
            receiveMessageNamedValue(message);
            break;
        case MAVLINK_MSG_ID_SYS_STATUS:
        {
                mavlink_sys_status_t state;
                mavlink_msg_sys_status_decode(&message, &state);
                emit loadChanged(this,state.load/10.0f);
                emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
                currentVoltage = state.voltage_battery/1000.0f;
LM's avatar
LM committed
                lpVoltage = filterVoltage(currentVoltage);
                if (startVoltage == 0) startVoltage = currentVoltage;
                timeRemaining = calculateTimeRemaining();
                if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
                    chargeLevel = state.battery_remaining;
LM's avatar
LM committed
                }
                //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
                emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
                emit voltageChanged(message.sysid, state.voltage_battery/1000);
LM's avatar
LM committed
                // LOW BATTERY ALARM
LM's avatar
LM committed
                    startLowBattAlarm();
LM's avatar
LM committed
                    stopLowBattAlarm();
                }
LM's avatar
LM committed
                // COMMUNICATIONS DROP RATE
                // FIXME
                emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
LM's avatar
LM committed
            break;
LM's avatar
LM committed
                mavlink_raw_imu_t raw;
                mavlink_msg_raw_imu_decode(&message, &raw);
                quint64 time = getUnixTime(raw.time_usec);
LM's avatar
LM committed

                emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
                emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
                emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
                emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
                emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
                emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
                emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
                emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
                emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
            }
            break;
LM's avatar
LM committed
                mavlink_scaled_imu_t scaled;
                mavlink_msg_scaled_imu_decode(&message, &scaled);
                quint64 time = getUnixTime(scaled.time_boot_ms);
LM's avatar
LM committed

                emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
                emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
                emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
                emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
                emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
                emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
                emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time);
                emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time);
                emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time);
LM's avatar
LM committed
            }
            break;
pixhawk's avatar
pixhawk committed
        case MAVLINK_MSG_ID_ATTITUDE:
            //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_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
LM's avatar
LM committed
                lastAttitude = time;
LM's avatar
LM committed
                roll = QGC::limitAngleToPMPIf(attitude.roll);
                pitch = QGC::limitAngleToPMPIf(attitude.pitch);
                yaw = QGC::limitAngleToPMPIf(attitude.yaw);
                emit valueChanged(uasId, "roll", "rad", roll, time);
                emit valueChanged(uasId, "pitch", "rad", pitch, time);
                emit valueChanged(uasId, "yaw", "rad", yaw, time);
                emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
                emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
                emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);

                // Emit in angles

                // Convert yaw angle to compass value
                // in 0 - 360 deg range
                float compass = (yaw/M_PI)*180.0+360.0f;
                while (compass > 360.0f) {
                    compass -= 360.0f;
                }
lm's avatar
lm committed

LM's avatar
LM committed
                attitudeKnown = true;
LM's avatar
LM committed
                emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
                emit valueChanged(uasId, "heading deg", "deg", compass, time);
                emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
                emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
                emit attitudeChanged(this, roll, pitch, yaw, time);
LM's avatar
LM committed
                emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
pixhawk's avatar
pixhawk committed
            }
LM's avatar
LM committed
            break;
lm's avatar
lm committed
        case MAVLINK_MSG_ID_HIL_CONTROLS:
            {
                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 valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
                emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
                emit valueChanged(uasId, "altitude", "m", hud.alt, time);
                emit valueChanged(uasId, "heading", "deg", hud.heading, time);
                emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
                emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
                emit thrustChanged(this, hud.throttle/100.0);

LM's avatar
LM committed
                    yaw = QGC::limitAngleToPMPId((((double)hud.heading-180.0)/360.0)*M_PI);
                    emit attitudeChanged(this, roll, pitch, yaw, time);
                }
LM's avatar
LM committed
                emit altitudeChanged(uasId, hud.alt);
                //yaw = (hud.heading-180.0f/360.0f)*M_PI;
                //emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
                emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, getUnixTime());
            }
            break;
        case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
            {
LM's avatar
LM committed
                mavlink_nav_controller_output_t nav;
                mavlink_msg_nav_controller_output_decode(&message, &nav);
                quint64 time = getUnixTime();
                // Update UI
                emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
                emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
                emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
                emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
                emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
                emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
                emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
                emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
            }
            break;
        case MAVLINK_MSG_ID_LOCAL_POSITION:
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_t pos;
                mavlink_msg_local_position_decode(&message, &pos);
                quint64 time = getUnixTime(pos.time_boot_ms);
LM's avatar
LM committed
                localX = pos.x;
                localY = pos.y;
                localZ = pos.z;
                emit valueChanged(uasId, "x", "m", pos.x, time);
                emit valueChanged(uasId, "y", "m", pos.y, time);
                emit valueChanged(uasId, "z", "m", pos.z, time);
                emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
                emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
                emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
                emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
                emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);

                //                qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
                //                qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;

                //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
lm's avatar
lm committed
            }
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 valueChanged(uasId, "latitude", "deg", latitude, time);
                emit valueChanged(uasId, "longitude", "deg", longitude, time);
                emit valueChanged(uasId, "altitude", "m", altitude, time);
                double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
                emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
                emit globalPositionChanged(this, latitude, longitude, altitude, time);
                emit speedChanged(this, speedX, speedY, speedZ, time);
                // Set internal state
                if (!positionLock) {
                    // If position was not locked before, notify positive
                    GAudioOutput::instance()->notifyPositive();
                }
                positionLock = true;
                //TODO fix this hack for forwarding of global position for patch antenna tracking
                forwardMessage(message);
LM's avatar
LM committed
            break;
LM's avatar
LM committed
                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);
LM's avatar
LM committed

                emit valueChanged(uasId, "gps latitude", "deg", pos.lat/(double)1E7, time);
                emit valueChanged(uasId, "gps longitude", "deg", pos.lon/(double)1E7, time);
                emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time);
                emit valueChanged(uasId, "gps eph", "m", pos.eph/(double)1E2, time);
                emit valueChanged(uasId, "gps epv", "m", pos.eph/(double)1E2, time);
                emit valueChanged(uasId, "gps fix", "raw", pos.fix_type, time);
                emit valueChanged(uasId, "gps course", "raw", pos.cog, time);
LM's avatar
LM committed

LM's avatar
LM committed
                if (pos.fix_type > 2) {
LM's avatar
LM committed
                    emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
                    latitude = pos.lat/(double)1E7;
                    longitude = pos.lon/(double)1E7;
                    altitude = pos.alt/1000.0;
                    positionLock = true;

                    // Check for NaN
                    int alt = pos.alt;
                    if (alt != alt) {
                        alt = 0;
                        emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
                    }
                    emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time);
                    // Smaller than threshold and not NaN
LM's avatar
LM committed

                    float vel = pos.vel/100.0f;

                    if (vel < 1000000 && !isnan(vel) && !isinf(vel)) {
                        emit valueChanged(uasId, "speed", "m/s", vel, time);
LM's avatar
LM committed
                        //qDebug() << "GOT GPS RAW";
                        // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
                    } else {
LM's avatar
LM committed
                        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
            break;
        case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
                mavlink_gps_global_origin_t pos;
                mavlink_msg_gps_global_origin_decode(&message, &pos);
LM's avatar
LM committed
                emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
LM's avatar
LM committed
            }
            break;
LM's avatar
LM committed
                mavlink_raw_pressure_t pressure;
                mavlink_msg_raw_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.time_usec);
LM's avatar
LM committed
                emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time);
                emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time);
                emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time);
            }
            break;
        case MAVLINK_MSG_ID_SCALED_PRESSURE:
            {
LM's avatar
LM committed
                mavlink_scaled_pressure_t pressure;
                mavlink_msg_scaled_pressure_decode(&message, &pressure);
                quint64 time = this->getUnixTime(pressure.time_boot_ms);
LM's avatar
LM committed
                emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
                emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
                emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
            }
            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);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time);
                emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time);
                emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time);
                emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time);
                emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time);
                emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time);
                emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time);
                emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time);
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((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
                QString parameterName = QString(bytes);
                int component = message.compid;
                mavlink_param_union_t val;
                val.param_float = value.param_value;

                // Convert to machine order if necessary
//#if MAVLINK_NEED_BYTE_SWAP
//   buffer[bindex]   = (b>>24)&0xff;
//   buffer[bindex+1] = (b>>16)&0xff;
//   buffer[bindex+2] = (b>>8)&0xff;
//   buffer[bindex+3] = (b & 0xff);
//#else
LM's avatar
LM committed

                // Insert component if necessary
                if (!parameters.contains(component))
                {
                    parameters.insert(component, new QMap<QString, QVariant>());
LM's avatar
LM committed
                }
LM's avatar
LM committed
                // Insert parameter into registry
                if (parameters.value(component)->contains(parameterName)) parameters.value(component)->remove(parameterName);
                // Insert with correct type
                switch (value.param_type)
                {
                case MAVLINK_TYPE_FLOAT:
                    parameters.value(component)->insert(parameterName, val.param_float);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_float);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_float);
                    break;
                case MAVLINK_TYPE_UINT32_T:
                    parameters.value(component)->insert(parameterName, val.param_uint32);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_uint32);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_uint32);
                    break;
                case MAVLINK_TYPE_INT32_T:
                    parameters.value(component)->insert(parameterName, val.param_int32);
                    // Emit change
                    emit parameterChanged(uasId, message.compid, parameterName, val.param_int32);
                    emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, val.param_int32);
                    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);
                emit textMessageReceived(uasId, message.compid, 0, tr("SUCCESS: Executed CMD: %1").arg(ack.command));
                emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
pixhawk's avatar
pixhawk committed
        case MAVLINK_MSG_ID_DEBUG:
            emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
pixhawk's avatar
pixhawk committed
            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);
LM's avatar
LM committed
                emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
                emit valueChanged(uasId, "att control roll", "rad", out.roll, time);
                emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time);
                emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time);
                emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time);
LM's avatar
LM committed
            }
            break;
LM's avatar
LM committed
                mavlink_waypoint_count_t wpc;
                mavlink_msg_waypoint_count_decode(&message, &wpc);
                if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
                    waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                }
LM's avatar
LM committed
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
            }
LM's avatar
LM committed
            break;
pixhawk's avatar
pixhawk committed

LM's avatar
LM committed
                mavlink_waypoint_t wp;
                mavlink_msg_waypoint_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_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
                    waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                }
LM's avatar
LM committed
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
LM's avatar
LM committed
            break;
pixhawk's avatar
pixhawk committed

LM's avatar
LM committed
                mavlink_waypoint_ack_t wpa;
                mavlink_msg_waypoint_ack_decode(&message, &wpa);
                if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
                    waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                }
LM's avatar
LM committed
            break;
        case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
            {
LM's avatar
LM committed
                mavlink_waypoint_request_t wpr;
                mavlink_msg_waypoint_request_decode(&message, &wpr);
                if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                {
LM's avatar
LM committed
                    waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                }
LM's avatar
LM committed
                else
                {
                    qDebug() << "Got waypoint message, but was not for me";
                }
pixhawk's avatar
pixhawk committed
            }
LM's avatar
LM committed
            break;
pixhawk's avatar
pixhawk committed

        case MAVLINK_MSG_ID_WAYPOINT_REACHED:
            {
LM's avatar
LM committed
                mavlink_waypoint_reached_t wpr;
                mavlink_msg_waypoint_reached_decode(&message, &wpr);
                waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
                QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
                GAudioOutput::instance()->say(text);
                emit textMessageReceived(message.sysid, message.compid, 0, text);
            }
            break;
pixhawk's avatar
pixhawk committed

        case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
            {
LM's avatar
LM committed
                mavlink_waypoint_current_t wpc;
                mavlink_msg_waypoint_current_decode(&message, &wpc);
                waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
            }
            break;
pixhawk's avatar
pixhawk committed

        case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
            {
LM's avatar
LM committed
                mavlink_local_position_setpoint_t p;
                mavlink_msg_local_position_setpoint_decode(&message, &p);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
            }
            break;
        case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
            {
LM's avatar
LM committed
                mavlink_servo_output_raw_t servos;
                mavlink_msg_servo_output_raw_decode(&message, &servos);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
                emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
                emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
                emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
                emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
                emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
                emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
                emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
            }
            break;
LM's avatar
LM committed
                QByteArray b;
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
lm's avatar
lm committed
                mavlink_msg_statustext_get_text(&message, b.data());
LM's avatar
LM committed
                //b.append('\0');
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
                //qDebug() << "RECEIVED STATUS:" << text;false
                //emit statusTextReceived(severity, text);
                emit textMessageReceived(uasId, message.compid, severity, text);
            }
            break;
#ifdef MAVLINK_ENABLED_PIXHAWK
        case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
LM's avatar
LM committed
                qDebug() << "RECIEVED ACK TO GET IMAGE";
                mavlink_data_transmission_handshake_t p;
                mavlink_msg_data_transmission_handshake_decode(&message, &p);
                imageSize = p.size;
                imagePackets = p.packets;
                imagePayload = p.payload;
                imageQuality = p.jpg_quality;
                imageType = p.type;
                imageStart = QGC::groundTimeMilliseconds();
            }
            break;
        case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
LM's avatar
LM committed
                mavlink_encapsulated_data_t img;
                mavlink_msg_encapsulated_data_decode(&message, &img);
                int seq = img.seqnr;
                int pos = seq * imagePayload;

                // Check if we have a valid transaction
                if (imagePackets == 0)
                {
                    // NO VALID TRANSACTION - ABORT
                    // Restart statemachine
                    imagePacketsArrived = 0;
                for (int i = 0; i < imagePayload; ++i)
                {
LM's avatar
LM committed
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
LM's avatar
LM committed
                ++imagePacketsArrived;
LM's avatar
LM committed
                // emit signal if all packets arrived
                if ((imagePacketsArrived >= imagePackets))
                {
                    // Restart statemachine
                    imagePacketsArrived = 0;
                    emit imageReady(this);
                    qDebug() << "imageReady emitted. all packets arrived";
                }
LM's avatar
LM committed
            break;
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(&message, &vect);
            QString str((const char*)vect.name);
            quint64 time = getUnixTime(vect.time_usec);
            emit valueChanged(uasId, str+".x", "raw", vect.x, time);
            emit valueChanged(uasId, str+".y", "raw", vect.y, time);
            emit valueChanged(uasId, str+".z", "raw", vect.z, time);
        }
        break;
        // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET
//        case MAVLINK_MSG_ID_MEMORY_VECT:
//        {
//            mavlink_memory_vect_t vect;
//            mavlink_msg_memory_vect_decode(&message, &vect);
//            QString str("mem_%1");
//            quint64 time = getUnixTime(0);
//            int16_t *mem0 = (int16_t *)&vect.value[0];
//            uint16_t *mem1 = (uint16_t *)&vect.value[0];
//            int32_t *mem2 = (int32_t *)&vect.value[0];
//            // uint32_t *mem3 = (uint32_t *)&vect.value[0]; causes overload problem
//            float *mem4 = (float *)&vect.value[0];
//            if ( vect.ver == 0) vect.type = 0, vect.ver = 1; else ;
//            if ( vect.ver == 1)
//            {
//                switch (vect.type) {
//                default:
//                case 0:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time);
//                    break;
//                case 1:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time);
//                    break;
//                case 2:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time);
//                    break;
//                case 3:
//                    for (int i = 0; i < 16; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time);
//                    break;
//                case 4:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 5:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time);
//                    break;
//                case 6:
//                    for (int i = 0; i < 8; i++)
//                        emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time);
//                    break;
//                }
//            }
//        }
//        break;
				//#ifdef MAVLINK_ENABLED_PIXHAWK
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST:
				//            {
				//                mavlink_point_of_interest_t poi;
				//                mavlink_msg_point_of_interest_decode(&message, &poi);
				//                emit poiFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN), poi.x, poi.y, poi.z);
				//            }
				//            break;
				//            case MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION:
				//            {
				//                mavlink_point_of_interest_connection_t poi;
				//                mavlink_msg_point_of_interest_connection_decode(&message, &poi);
				//                emit poiConnectionFound(this, poi.type, poi.color, QString((QChar*)poi.name, MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN), poi.x1, poi.y1, poi.z1, poi.x2, poi.y2, poi.z2);
				//            }
				//            break;
				//#endif
lm's avatar
lm committed
#ifdef MAVLINK_ENABLED_UALBERTA
        case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
            {
LM's avatar
LM committed
                mavlink_nav_filter_bias_t bias;
                mavlink_msg_nav_filter_bias_decode(&message, &bias);
                quint64 time = getUnixTime();
                emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time);
                emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time);
                emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time);
                emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time);
                emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time);
                emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time);
            }
            break;
        case MAVLINK_MSG_ID_RADIO_CALIBRATION:
            {
LM's avatar
LM committed
                mavlink_radio_calibration_t radioMsg;
                mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                QVector<uint16_t> aileron;
                QVector<uint16_t> elevator;
                QVector<uint16_t> rudder;
                QVector<uint16_t> gyro;
                QVector<uint16_t> pitch;
                QVector<uint16_t> throttle;
LM's avatar
LM committed