Skip to content
Snippets Groups Projects
UAS.cc 76.4 KiB
Newer Older
  • Learn to ignore specific revisions
  • /****************************************************************************
     *
     *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
     *
     * QGroundControl is licensed according to the terms in the file
     * COPYING.md in the root of the source code directory.
     *
     ****************************************************************************/
    
    
    
    /**
     * @file
     *   @brief Represents one unmanned aerial vehicle
     *
     *   @author Lorenz Meier <mavteam@student.ethz.ch>
     *
     */
    
    #include <QList>
    #include <QTimer>
    #include <QSettings>
    #include <iostream>
    #include <QDebug>
    
    #include <cmath>
    #include <qmath.h>
    
    #include "UAS.h"
    #include "LinkInterface.h"
    
    #include "HomePositionManager.h"
    
    #include "QGC.h"
    #include "GAudioOutput.h"
    #include "MAVLinkProtocol.h"
    #include "QGCMAVLink.h"
    #include "LinkManager.h"
    
    Gus Grubba's avatar
    Gus Grubba committed
    #ifndef NO_SERIAL_LINK
    
    #include "SerialLink.h"
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    Don Gagne's avatar
    Don Gagne committed
    #include "FirmwarePluginManager.h"
    
    #include "QGCLoggingCategory.h"
    
    #include "Vehicle.h"
    
    #include "Joystick.h"
    
    #include "QGCApplication.h"
    
    QGC_LOGGING_CATEGORY(UASLog, "UASLog")
    
    /**
    * 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
    
    UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(),
    
        lipoFull(4.2f),
        lipoEmpty(3.5f),
    
        uasId(vehicle->id()),
    
        unknownPackets(),
        mavlink(protocol),
    
        receiveDropRate(0),
        sendDropRate(0),
    
        status(-1),
    
        startTime(QGC::groundTimeMilliseconds()),
    
        onboardTimeOffset(0),
    
        controlRollManual(true),
        controlPitchManual(true),
        controlYawManual(true),
        controlThrustManual(true),
        manualRollAngle(0),
        manualPitchAngle(0),
        manualYawAngle(0),
        manualThrust(0),
    
    
        isGlobalPositionKnown(false),
    
    
        latitude(0.0),
        longitude(0.0),
        altitudeAMSL(0.0),
    
        altitudeAMSLFT(0.0),
    
        satRawHDOP(1e10f),
        satRawVDOP(1e10f),
        satRawCOG(0.0),
    
    
    Don Gagne's avatar
    Don Gagne committed
        globalEstimatorActive(false),
    
        latitude_gps(0.0),
        longitude_gps(0.0),
        altitude_gps(0.0),
    
    Don Gagne's avatar
    Don Gagne committed
        airSpeed(std::numeric_limits<double>::quiet_NaN()),
        groundSpeed(std::numeric_limits<double>::quiet_NaN()),
    
        fileManager(this, vehicle),
    
    Don Gagne's avatar
    Don Gagne committed
    
    
        attitudeKnown(false),
        attitudeStamped(false),
        lastAttitude(0),
    
        roll(0.0),
        pitch(0.0),
        yaw(0.0),
    
    
    Don Gagne's avatar
    Don Gagne committed
        imagePackets(0),    // We must initialize to 0, otherwise extended data packets maybe incorrectly thought to be images
    
    
    Don Gagne's avatar
    Don Gagne committed
        blockHomePositionChanges(false),
        receivedMode(false),
    
    
        // Note variances calculated from flight case from this log: http://dash.oznet.ch/view/MRjW8NUNYQSuSZkbn8dEjY
        // TODO: calibrate stand-still pixhawk variances
    
    dogmaphobic's avatar
    dogmaphobic committed
        yacc_var(0.7048f),
    
    dogmaphobic's avatar
    dogmaphobic committed
        rollspeed_var(0.8126f),
        pitchspeed_var(0.6145f),
        yawspeed_var(0.5852f),
    
        xmag_var(0.2393f),
        ymag_var(0.2283f),
        zmag_var(0.1665f),
        abs_pressure_var(0.5802f),
        diff_pressure_var(0.5802f),
        pressure_alt_var(0.5802f),
        temperature_var(0.7145f),
    
        xacc_var(0.0f),
        yacc_var(0.0f),
        zacc_var(0.0f),
        rollspeed_var(0.0f),
        pitchspeed_var(0.0f),
        yawspeed_var(0.0f),
        xmag_var(0.0f),
        ymag_var(0.0f),
        zmag_var(0.0f),
        abs_pressure_var(0.0f),
        diff_pressure_var(0.0f),
        pressure_alt_var(0.0f),
        temperature_var(0.0f),
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    
        // The protected members.
    
        connectionLost(false),
        lastVoltageWarning(0),
        lastNonNullTime(0),
        onboardTimeOffsetInvalidCount(0),
    
        sensorHil(false),
        lastSendTimeGPS(0),
    
        lastSendTimeSensors(0),
    
        lastSendTimeOpticalFlow(0),
    
        _vehicle(vehicle),
        _firmwarePluginManager(firmwarePluginManager)
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        for (unsigned int i = 0; i<255;++i)
        {
            componentID[i] = -1;
            componentMulti[i] = false;
        }
    
        connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
    
        color = UASInterface::getNextColor();
    }
    
    /**
    * @ return the id of the uas
    */
    int UAS::getUASID() const
    {
        return uasId;
    }
    
    
    void UAS::receiveMessage(mavlink_message_t message)
    
    {
        if (!components.contains(message.compid))
        {
            QString componentName;
    
            switch (message.compid)
            {
            case MAV_COMP_ID_ALL:
            {
                componentName = "ANONYMOUS";
                break;
            }
            case MAV_COMP_ID_IMU:
            {
                componentName = "IMU #1";
                break;
            }
            case MAV_COMP_ID_CAMERA:
            {
                componentName = "CAMERA";
                break;
            }
            case MAV_COMP_ID_MISSIONPLANNER:
            {
                componentName = "MISSIONPLANNER";
                break;
            }
            }
    
            components.insert(message.compid, componentName);
        }
    
        //    qDebug() << "UAS RECEIVED from" << message.sysid << "component" << message.compid << "msg id" << message.msgid << "seq no" << message.seq;
    
        // 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))
        {
            QString uasState;
            QString stateDescription;
    
            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;
    
    
            switch (message.msgid)
            {
            case MAVLINK_MSG_ID_HEARTBEAT:
            {
                if (multiComponentSourceDetected && wrongComponent)
                {
                    break;
                }
                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);
    
    
                if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
                {
                    this->status = state.system_status;
                    getStatusForCode((int)state.system_status, uasState, stateDescription);
                    emit statusChanged(this, uasState, stateDescription);
                    emit statusChanged(this->status);
                }
    
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                // We got the mode
                receivedMode = true;
    
            case MAVLINK_MSG_ID_SYS_STATUS:
            {
                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);
    
    
                emit loadChanged(this,state.load/10.0f);
    
                emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
    
    
                // 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)
                {
                    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);
            }
    
                break;
            case MAVLINK_MSG_ID_ATTITUDE:
            {
                mavlink_attitude_t attitude;
                mavlink_msg_attitude_decode(&message, &attitude);
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
    
                emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(attitude.roll), QGC::limitAngleToPMPIf(attitude.pitch), QGC::limitAngleToPMPIf(attitude.yaw), time);
    
                if (!wrongComponent)
                {
                    lastAttitude = time;
    
                    setRoll(QGC::limitAngleToPMPIf(attitude.roll));
                    setPitch(QGC::limitAngleToPMPIf(attitude.pitch));
                    setYaw(QGC::limitAngleToPMPIf(attitude.yaw));
    
                    attitudeKnown = true;
                    emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
                    emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
                }
            }
                break;
            case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
            {
                mavlink_attitude_quaternion_t attitude;
                mavlink_msg_attitude_quaternion_decode(&message, &attitude);
                quint64 time = getUnixReferenceTime(attitude.time_boot_ms);
    
                double a = attitude.q1;
                double b = attitude.q2;
                double c = attitude.q3;
                double d = attitude.q4;
    
                double aSq = a * a;
                double bSq = b * b;
                double cSq = c * c;
                double dSq = d * d;
                float dcm[3][3];
                dcm[0][0] = aSq + bSq - cSq - dSq;
                dcm[0][1] = 2.0 * (b * c - a * d);
                dcm[0][2] = 2.0 * (a * c + b * d);
                dcm[1][0] = 2.0 * (b * c + a * d);
                dcm[1][1] = aSq - bSq + cSq - dSq;
                dcm[1][2] = 2.0 * (c * d - a * b);
                dcm[2][0] = 2.0 * (b * d - a * c);
                dcm[2][1] = 2.0 * (a * b + c * d);
                dcm[2][2] = aSq - bSq - cSq + dSq;
    
                float phi, theta, psi;
                theta = asin(-dcm[2][0]);
    
                if (fabs(theta - M_PI_2) < 1.0e-3f) {
                    phi = 0.0f;
                    psi = (atan2(dcm[1][2] - dcm[0][1],
                            dcm[0][2] + dcm[1][1]) + phi);
    
                } else if (fabs(theta + M_PI_2) < 1.0e-3f) {
                    phi = 0.0f;
                    psi = atan2f(dcm[1][2] - dcm[0][1],
                              dcm[0][2] + dcm[1][1] - phi);
    
                } else {
                    phi = atan2f(dcm[2][1], dcm[2][2]);
                    psi = atan2f(dcm[1][0], dcm[0][0]);
                }
    
                emit attitudeChanged(this, message.compid, QGC::limitAngleToPMPIf(phi),
                                     QGC::limitAngleToPMPIf(theta),
                                     QGC::limitAngleToPMPIf(psi), time);
    
                if (!wrongComponent)
                {
                    lastAttitude = time;
                    setRoll(QGC::limitAngleToPMPIf(phi));
                    setPitch(QGC::limitAngleToPMPIf(theta));
                    setYaw(QGC::limitAngleToPMPIf(psi));
    
                    emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
    
                    emit attitudeRotationRatesChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
    
                }
            }
                break;
            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);
            }
                break;
            case MAVLINK_MSG_ID_VFR_HUD:
            {
                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);
    
                if (!attitudeKnown)
                {
    
                    setYaw(QGC::limitAngleToPMPId((((double)hud.heading)/180.0)*M_PI));
    
                    emit attitudeChanged(this, getRoll(), getPitch(), getYaw(), time);
    
                setAltitudeAMSL(hud.alt);
                setGroundSpeed(hud.groundspeed);
    
                if (!qIsNaN(hud.airspeed))
    
                    setAirSpeed(hud.airspeed);
                speedZ = -hud.climb;
    
    Don Gagne's avatar
    Don Gagne committed
                emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
    
                emit speedChanged(this, groundSpeed, airSpeed, time);
    
            }
                break;
            case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
                //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;
            {
                mavlink_local_position_ned_t pos;
                mavlink_msg_local_position_ned_decode(&message, &pos);
                quint64 time = getUnixTime(pos.time_boot_ms);
    
                if (!wrongComponent)
                {
    
                    speedX = pos.vx;
                    speedY = pos.vy;
                    speedZ = pos.vz;
    
                    emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
    
                }
            }
                break;
            case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
            {
                mavlink_global_vision_position_estimate_t pos;
                mavlink_msg_global_vision_position_estimate_decode(&message, &pos);
                quint64 time = getUnixTime(pos.usec);
                emit attitudeChanged(this, message.compid, pos.roll, pos.pitch, pos.yaw, time);
            }
                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;
            {
                mavlink_global_position_int_t pos;
                mavlink_msg_global_position_int_decode(&message, &pos);
    
                quint64 time = getUnixTime();
    
                setLatitude(pos.lat/(double)1E7);
                setLongitude(pos.lon/(double)1E7);
    
                setAltitudeRelative(pos.relative_alt/1000.0);
    
                globalEstimatorActive = true;
    
                speedX = pos.vx/100.0;
                speedY = pos.vy/100.0;
                speedZ = pos.vz/100.0;
    
    Don Gagne's avatar
    Don Gagne committed
                emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
                emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
    
                // We had some frame mess here, global and local axes were mixed.
    
                emit velocityChanged_NED(this, speedX, speedY, speedZ, time);
    
                setGroundSpeed(qSqrt(speedX*speedX+speedY*speedY));
                emit speedChanged(this, groundSpeed, airSpeed, time);
    
    
                isGlobalPositionKnown = true;
            }
                break;
            case MAVLINK_MSG_ID_GPS_RAW_INT:
            {
                mavlink_gps_raw_int_t pos;
                mavlink_msg_gps_raw_int_decode(&message, &pos);
    
                quint64 time = getUnixTime(pos.time_usec);
    
                // TODO: track localization state not only for gps but also for other loc. sources
                int loc_type = pos.fix_type;
                if (loc_type == 1)
                {
    
                setSatelliteCount(pos.satellites_visible);
    
                    latitude_gps  = pos.lat/(double)1E7;
    
                    longitude_gps = pos.lon/(double)1E7;
    
                    altitude_gps  = pos.alt/1000.0;
    
                    // If no GLOBAL_POSITION_INT messages ever received, use these raw GPS values instead.
    
                    if (!globalEstimatorActive) {
    
                        setLatitude(latitude_gps);
                        setLongitude(longitude_gps);
    
    Don Gagne's avatar
    Don Gagne committed
                        emit globalPositionChanged(this, getLatitude(), getLongitude(), getAltitudeAMSL(), time);
                        emit altitudeChanged(this, altitudeAMSL, altitudeRelative, -speedZ, time);
    
                        float vel = pos.vel/100.0f;
                        // Smaller than threshold and not NaN
    
                        if ((vel < 1000000) && !qIsNaN(vel) && !qIsInf(vel)) {
    
                            setGroundSpeed(vel);
    
                            emit speedChanged(this, groundSpeed, airSpeed, time);
                        } else {
    
                            emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_NOTICE, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(vel));
    
                double dtmp;
                //-- Raw GPS data
                dtmp = pos.eph == 0xFFFF ? 1e10f : pos.eph / 100.0;
                if(dtmp != satRawHDOP)
                {
                    satRawHDOP = dtmp;
                    emit satRawHDOPChanged(satRawHDOP);
                }
                dtmp = pos.epv == 0xFFFF ? 1e10f : pos.epv / 100.0;
                if(dtmp != satRawVDOP)
                {
                    satRawVDOP = dtmp;
                    emit satRawVDOPChanged(satRawVDOP);
                }
                dtmp = pos.cog == 0xFFFF ? 0.0 : pos.cog / 100.0;
                if(dtmp != satRawCOG)
                {
                    satRawCOG = dtmp;
                    emit satRawCOGChanged(satRawCOG);
                }
    
    
                // Emit this signal after the above signals. This way a trigger on gps lock signal which then asks for vehicle position
                // gets a good position.
                emit localizationChanged(this, loc_type);
    
            }
                break;
            case MAVLINK_MSG_ID_GPS_STATUS:
            {
                mavlink_gps_status_t pos;
                mavlink_msg_gps_status_decode(&message, &pos);
                for(int i = 0; i < (int)pos.satellites_visible; i++)
                {
                    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]));
                }
    
                setSatelliteCount(pos.satellites_visible);
    
            case MAVLINK_MSG_ID_PARAM_VALUE:
            {
    
                mavlink_param_value_t rawValue;
                mavlink_msg_param_value_decode(&message, &rawValue);
                QByteArray bytes(rawValue.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);
    
                mavlink_param_union_t paramVal;
                paramVal.param_float = rawValue.param_value;
                paramVal.type = rawValue.param_type;
    
                processParamValueMsg(message, parameterName,rawValue,paramVal);
             }
    
                mavlink_attitude_target_t out;
                mavlink_msg_attitude_target_decode(&message, &out);
                float roll, pitch, yaw;
                mavlink_quaternion_to_euler(out.q, &roll, &pitch, &yaw);
    
                quint64 time = getUnixTimeFromMs(out.time_boot_ms);
    
                emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, out.thrust, time);
    
    
                // For plotting emit roll sp, pitch sp and yaw sp values
    
                emit valueChanged(uasId, "roll sp", "rad", roll, time);
                emit valueChanged(uasId, "pitch sp", "rad", pitch, time);
                emit valueChanged(uasId, "yaw sp", "rad", yaw, time);
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
            case MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED:
    
            {
                if (multiComponentSourceDetected && wrongComponent)
                {
                    break;
                }
    
                mavlink_position_target_local_ned_t p;
                mavlink_msg_position_target_local_ned_decode(&message, &p);
                quint64 time = getUnixTimeFromMs(p.time_boot_ms);
                emit positionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */, time);
    
            case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
    
                mavlink_set_position_target_local_ned_t p;
                mavlink_msg_set_position_target_local_ned_decode(&message, &p);
                emit userPositionSetPointsChanged(uasId, p.x, p.y, p.z, 0/* XXX remove yaw and move it to attitude */);
    
            }
                break;
            case MAVLINK_MSG_ID_STATUSTEXT:
            {
                QByteArray b;
    
                b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
    
                mavlink_msg_statustext_get_text(&message, b.data());
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
                // Ensure NUL-termination
                b[b.length()-1] = '\0';
    
                QString text = QString(b);
                int severity = mavlink_msg_statustext_get_severity(&message);
    
    
    dogmaphobic's avatar
    dogmaphobic committed
            // If the message is NOTIFY or higher severity, or starts with a '#',
            // then read it aloud.
    
                if (text.startsWith("#") || severity <= MAV_SEVERITY_NOTICE)
    
                    emit textMessageReceived(uasId, message.compid, severity, text);
    
                    _say(text.toLower(), severity);
    
                }
                else
                {
                    emit textMessageReceived(uasId, message.compid, severity, text);
                }
            }
                break;
    
            case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
            {
                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;
                imageWidth = p.width;
                imageHeight = p.height;
                imageStart = QGC::groundTimeMilliseconds();
    
                imagePacketsArrived = 0;
    
    
            }
                break;
    
            case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
            {
                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;
    
    Don Gagne's avatar
    Don Gagne committed
                    break;
    
                }
    
                for (int i = 0; i < imagePayload; ++i)
                {
                    if (pos <= imageSize) {
                        imageRecBuffer[pos] = img.data[i];
                    }
                    ++pos;
                }
    
                ++imagePacketsArrived;
    
                // emit signal if all packets arrived
    
                if (imagePacketsArrived >= imagePackets)
    
    Don Gagne's avatar
    Don Gagne committed
                    imagePackets = 0;
                    imagePacketsArrived = 0;
    
                    emit imageReady(this);
                }
            }
                break;
    
            case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
    
            {
                mavlink_nav_controller_output_t p;
                mavlink_msg_nav_controller_output_decode(&message,&p);
                setDistToWaypoint(p.wp_dist);
    
                setBearingToWaypoint(p.nav_bearing);
                emit navigationControllerErrorsChanged(this, p.alt_error, p.aspd_error, p.xtrack_error);
    
                emit NavigationControllerDataChanged(this, p.nav_roll, p.nav_pitch, p.nav_bearing, p.target_bearing, p.wp_dist);
    
    dogmaphobic's avatar
    dogmaphobic committed
    
            case MAVLINK_MSG_ID_LOG_ENTRY:
            {
                mavlink_log_entry_t log;
                mavlink_msg_log_entry_decode(&message, &log);
                emit logEntry(this, log.time_utc, log.size, log.id, log.num_logs, log.last_log_num);
            }
                break;
    
            case MAVLINK_MSG_ID_LOG_DATA:
            {
                mavlink_log_data_t log;
                mavlink_msg_log_data_decode(&message, &log);
                emit logData(this, log.ofs, log.id, log.count, log.data);
            }
                break;
    
    
    void UAS::startCalibration(UASInterface::StartCalibrationType calType)
    
        if (!_vehicle) {
            return;
        }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        int gyroCal = 0;
        int magCal = 0;
        int airspeedCal = 0;
        int radioCal = 0;
        int accelCal = 0;
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        switch (calType) {
    
        case StartCalibrationGyro:
            gyroCal = 1;
            break;
        case StartCalibrationMag:
            magCal = 1;
            break;
        case StartCalibrationAirspeed:
            airspeedCal = 1;
            break;
        case StartCalibrationRadio:
            radioCal = 1;
            break;
        case StartCalibrationCopyTrims:
            radioCal = 2;
            break;
        case StartCalibrationAccel:
            accelCal = 1;
            break;
        case StartCalibrationLevel:
            accelCal = 2;
            break;
        case StartCalibrationEsc:
            escCal = 1;
            break;
        case StartCalibrationUavcanEsc:
            escCal = 2;
            break;
        case StartCalibrationCompassMot:
            airspeedCal = 1; // ArduPilot, bit of a hack
            break;
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        mavlink_message_t msg;
    
        mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
                                           mavlink->getComponentId(),
                                           _vehicle->priorityLink()->mavlinkChannel(),
                                           &msg,
                                           uasId,
                                           _vehicle->defaultComponentId(),   // target component
                                           MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                           0,                                // 0=first transmission of command
                                           gyroCal,                          // gyro cal
                                           magCal,                           // mag cal
                                           0,                                // ground pressure
                                           radioCal,                         // radio cal
                                           accelCal,                         // accel cal
                                           airspeedCal,                      // PX4: airspeed cal, ArduPilot: compass mot
                                           escCal);                          // esc cal
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    
    void UAS::stopCalibration(void)
    
        if (!_vehicle) {
            return;
        }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
                                           mavlink->getComponentId(),
                                           _vehicle->priorityLink()->mavlinkChannel(),
                                           &msg,
                                           uasId,
                                           _vehicle->defaultComponentId(),   // target component
                                           MAV_CMD_PREFLIGHT_CALIBRATION,    // command id
                                           0,                                // 0=first transmission of command
                                           0,                                // gyro cal
                                           0,                                // mag cal
                                           0,                                // ground pressure
                                           0,                                // radio cal
                                           0,                                // accel cal
                                           0,                                // airspeed cal
                                           0);                               // unused
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    
    void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
    {
    
        if (!_vehicle) {
            return;
        }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
       int actuatorCal = 0;
    
    
        switch (calType) {
            case StartBusConfigActuators:
                actuatorCal = 1;
    
            break;
            case EndBusConfigActuators:
                actuatorCal = 0;
            break;
    
        }
    
        mavlink_message_t msg;
    
        mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
                                           mavlink->getComponentId(),
                                           _vehicle->priorityLink()->mavlinkChannel(),
                                           &msg,
                                           uasId,
                                           _vehicle->defaultComponentId(),   // target component
                                           MAV_CMD_PREFLIGHT_UAVCAN,         // command id
                                           0,                                // 0=first transmission of command
                                           actuatorCal,                      // actuators
                                           0,
                                           0,
                                           0,
                                           0,
                                           0,
                                           0);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    
    }
    
    void UAS::stopBusConfig(void)
    {
    
        if (!_vehicle) {
            return;
        }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
    
        mavlink_message_t msg;
    
        mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
                                           mavlink->getComponentId(),
                                           _vehicle->priorityLink()->mavlinkChannel(),
                                           &msg,
                                           uasId,
                                           _vehicle->defaultComponentId(),   // target component
                                           MAV_CMD_PREFLIGHT_UAVCAN,         // command id
                                           0,                                // 0=first transmission of command
                                           0,
                                           0,
                                           0,
                                           0,
                                           0,
                                           0,
                                           0);
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    
    /**
    * Check if time is smaller than 40 years, assuming no system without Unix
    
    * timestamp runs longer than 40 years continuously without reboot. In worst case
    * this will add/subtract the communication delay between GCS and MAV, it will
    * never alter the timestamp in a safety critical way.
    */
    quint64 UAS::getUnixReferenceTime(quint64 time)
    {
        // Same as getUnixTime, but does not react to attitudeStamped mode
        if (time == 0)
        {
            //        qDebug() << "XNEW time:" <<QGC::groundTimeMilliseconds();
            return QGC::groundTimeMilliseconds();
        }
        // Check if time is smaller than 40 years,
        // assuming no system without Unix timestamp
        // runs longer than 40 years continuously without
        // reboot. In worst case this will add/subtract the
        // communication delay between GCS and MAV,
        // it will never alter the timestamp in a safety
        // critical way.
        //
        // Calculation:
        // 40 years
        // 365 days
        // 24 hours
        // 60 minutes
        // 60 seconds
        // 1000 milliseconds
        // 1000 microseconds
    #ifndef _MSC_VER
        else if (time < 1261440000000000LLU)
    #else
        else if (time < 1261440000000000)
    #endif
        {
            //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
            if (onboardTimeOffset == 0)
            {
                onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
            }
            return time/1000 + onboardTimeOffset;
        }
        else
        {
            // Time is not zero and larger than 40 years -> has to be
            // a Unix epoch timestamp. Do nothing.
            return time/1000;
        }
    }
    
    /**
    * @warning If attitudeStamped is enabled, this function will not actually return
    
    * the precise time stamp of this measurement augmented to UNIX time, but will
    
    * MOVE the timestamp IN TIME to match the last measured attitude. There is no
    
    * reason why one would want this, except for system setups where the onboard
    
    * clock is not present or broken and datasets should be collected that are still
    
    * roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE
    
    * SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
    */
    quint64 UAS::getUnixTimeFromMs(quint64 time)
    {
        return getUnixTime(time*1000);
    }
    
    /**
    * @warning If attitudeStamped is enabled, this function will not actually return
    
    * the precise time stam of this measurement augmented to UNIX time, but will
    * MOVE the timestamp IN TIME to match the last measured attitude. There is no
    * reason why one would want this, except for system setups where the onboard
    * clock is not present or broken and datasets should be collected that are
    
    * still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED
    * RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL!
    */
    quint64 UAS::getUnixTime(quint64 time)
    {
        quint64 ret = 0;
        if (attitudeStamped)
        {
            ret = lastAttitude;
        }
    
        if (time == 0)
        {
            ret = QGC::groundTimeMilliseconds();
        }
        // Check if time is smaller than 40 years,
        // assuming no system without Unix timestamp
        // runs longer than 40 years continuously without
        // reboot. In worst case this will add/subtract the
        // communication delay between GCS and MAV,
        // it will never alter the timestamp in a safety
        // critical way.
        //
        // Calculation:
        // 40 years