Skip to content
Snippets Groups Projects
UAS.cc 57.5 KiB
Newer Older
  • Learn to ignore specific revisions
  • pixhawk's avatar
    pixhawk committed
    /*=====================================================================
    
    
    lm's avatar
    lm committed
    QGroundControl Open Source Ground Control Station
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
    (c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
    This file is part of the QGROUNDCONTROL project
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
        QGROUNDCONTROL is free software: you can redistribute it and/or modify
    
    pixhawk's avatar
    pixhawk committed
        it under the terms of the GNU General Public License as published by
        the Free Software Foundation, either version 3 of the License, or
        (at your option) any later version.
    
    
    lm's avatar
    lm committed
        QGROUNDCONTROL is distributed in the hope that it will be useful,
    
    pixhawk's avatar
    pixhawk committed
        but WITHOUT ANY WARRANTY; without even the implied warranty of
        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
        GNU General Public License for more details.
    
        You should have received a copy of the GNU General Public License
    
    lm's avatar
    lm committed
        along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
    
    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 <iostream>
    #include <QDebug>
    #include <cmath>
    #include "UAS.h"
    #include "LinkInterface.h"
    #include "UASManager.h"
    #include "MG.h"
    
    #include "QGC.h"
    
    pixhawk's avatar
    pixhawk committed
    #include "GAudioOutput.h"
    
    #include "MAVLinkProtocol.h"
    
    pixhawk's avatar
    pixhawk committed
    #include "QGCMAVLink.h"
    
    pixhawk's avatar
    pixhawk committed
    
    
    UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
    
    pixhawk's avatar
    pixhawk committed
            startTime(MG::TIME::getGroundTimeNow()),
            commStatus(COMM_DISCONNECTED),
            name(""),
            links(new QList<LinkInterface*>()),
    
            waypointManager(*this),
    
    pixhawk's avatar
    pixhawk committed
            thrustSum(0),
    
    pixhawk's avatar
    pixhawk committed
            thrustMax(10),
    
    pixhawk's avatar
    pixhawk committed
            startVoltage(0),
    
            currentVoltage(12.0f),
            lpVoltage(12.0f),
    
    pixhawk's avatar
    pixhawk committed
            mode(MAV_MODE_UNINIT),
            status(MAV_STATE_UNINIT),
            onboardTimeOffset(0),
    
    pixhawk's avatar
    pixhawk committed
            controlRollManual(true),
            controlPitchManual(true),
            controlYawManual(true),
            controlThrustManual(true),
    
    pixhawk's avatar
    pixhawk committed
            manualRollAngle(0),
            manualPitchAngle(0),
            manualYawAngle(0),
    
    lm's avatar
    lm committed
            manualThrust(0),
            receiveDropRate(0),
    
    lm's avatar
    lm committed
            sendDropRate(0),
    
            lowBattAlarm(false),
            positionLock(false),
    
    lm's avatar
    lm committed
            localX(0),
            localY(0),
            localZ(0),
            roll(0),
            pitch(0),
            yaw(0),
    
    pixhawk's avatar
    pixhawk committed
    {
    
        color = UASInterface::getNextColor();
    
    pixhawk's avatar
    pixhawk committed
        setBattery(LIPOLY, 3);
    
        statusTimeout->setInterval(500);
        connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
    
    pixhawk's avatar
    pixhawk committed
    }
    
    UAS::~UAS()
    {
        delete links;
    }
    
    
    pixhawk's avatar
    pixhawk committed
    {
        return uasId;
    }
    
    
    void UAS::updateState()
    {
        // Position lock is set by the MAVLink message handler
        // if no position lock is available, indicate an error
        if (positionLock)
        {
            positionLock = false;
        }
        else
        {
    
    pixhawk's avatar
    pixhawk committed
            if (mode > (uint8_t)MAV_MODE_LOCKED && positionLock)
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setSelected()
    {
        UASManager::instance()->setActiveUAS(this);
    }
    
    void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
    {
        if (!links->contains(link))
        {
            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
    
    
    pixhawk's avatar
    pixhawk committed
        if (message.sysid == uasId)
        {
            QString uasState;
            QString stateDescription;
            QString patternPath;
            switch (message.msgid)
            {
            case MAVLINK_MSG_ID_HEARTBEAT:
                emit heartbeat(this);
                // Set new type if it has changed
    
    pixhawk's avatar
    pixhawk committed
                if (this->type != mavlink_msg_heartbeat_get_type(&message))
    
    pixhawk's avatar
    pixhawk committed
                {
    
    pixhawk's avatar
    pixhawk committed
                    this->type = mavlink_msg_heartbeat_get_type(&message);
    
    pixhawk's avatar
    pixhawk committed
                    emit systemTypeSet(this, type);
                }
                break;
            case MAVLINK_MSG_ID_BOOT:
                getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
                emit statusChanged(this, uasState, stateDescription);
                onboardTimeOffset = 0; // Reset offset measurement
                break;
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_SYS_STATUS:
                {
    
    pixhawk's avatar
    pixhawk committed
                    mavlink_sys_status_t state;
                    mavlink_msg_sys_status_decode(&message, &state);
    
    pixhawk's avatar
    pixhawk committed
                    // FIXME
    
                    //qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
    
    pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
                    QString audiostring = "System " + QString::number(this->getUASID());
                    QString stateAudio = "";
                    QString modeAudio = "";
                    bool statechanged = false;
                    bool modechanged = false;
    
    pixhawk's avatar
    pixhawk committed
                    if (state.status != this->status)
    
    pixhawk's avatar
    pixhawk committed
                    {
    
    pixhawk's avatar
    pixhawk committed
                        statechanged = true;
    
    lm's avatar
    lm committed
                        this->status = (int)state.status;
    
    pixhawk's avatar
    pixhawk committed
                        getStatusForCode((int)state.status, uasState, stateDescription);
                        emit statusChanged(this, uasState, stateDescription);
    
                        emit statusChanged(this->status);
    
                        emit loadChanged(this,state.load/10.0f);
                        emit UAS::valueChanged(this, "Load", ((float)state.load)/1000.0f, MG::TIME::getGroundTimeNow());
    
                        stateAudio = " changed status to " + uasState;
    
    lm's avatar
    lm committed
                    if (this->mode != static_cast<unsigned int>(state.mode))
    
    pixhawk's avatar
    pixhawk committed
                    {
                        modechanged = true;
    
    lm's avatar
    lm committed
                        this->mode = static_cast<unsigned int>(state.mode);
    
    pixhawk's avatar
    pixhawk committed
                        QString mode;
    
    
    lm's avatar
    lm committed
                        switch (state.mode)
    
    pixhawk's avatar
    pixhawk committed
                        {
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_LOCKED:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "LOCKED MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_MANUAL:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "MANUAL MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_AUTO:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "AUTO MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_GUIDED:
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_READY:
    
    lm's avatar
    lm committed
                            mode = "READY";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_TEST1:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "TEST1 MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_TEST2:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "TEST2 MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_TEST3:
    
    pixhawk's avatar
    pixhawk committed
                            mode = "TEST3 MODE";
                            break;
    
    lm's avatar
    lm committed
                        case (uint8_t)MAV_MODE_RC_TRAINING:
                            mode = "RC TRAINING MODE";
                            break;
    
    pixhawk's avatar
    pixhawk committed
                        default:
                            mode = "UNINIT MODE";
                            break;
                        }
    
                        emit modeChanged(this->getUASID(), mode, "");
                        modeAudio = " is now in " + mode;
                    }
    
    lm's avatar
    lm committed
                    currentVoltage = state.vbat/1000.0f;
    
    pixhawk's avatar
    pixhawk committed
                    lpVoltage = filterVoltage(currentVoltage);
    
    pixhawk's avatar
    pixhawk committed
                    if (startVoltage == 0) startVoltage = currentVoltage;
                    timeRemaining = calculateTimeRemaining();
                    //qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
    
    pixhawk's avatar
    pixhawk committed
                    emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
    
    pixhawk's avatar
    pixhawk committed
                    emit voltageChanged(message.sysid, state.vbat/1000.0f);
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
                    // LOW BATTERY ALARM
                    float chargeLevel = getChargeLevel();
    
                    if (chargeLevel <= 20.0f)
    
    lm's avatar
    lm committed
                    {
                        startLowBattAlarm();
                    }
                    else
                    {
                        stopLowBattAlarm();
                    }
    
    
    lm's avatar
    lm committed
                    // COMMUNICATIONS DROP RATE
    
                    emit dropRateChanged(this->getUASID(), state.packet_drop);
    
                    //qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop;
    
    lm's avatar
    lm committed
    
                    // AUDIO
    
    pixhawk's avatar
    pixhawk committed
                    if (modechanged && statechanged)
                    {
                        // Output both messages
                        audiostring += modeAudio + " and " + stateAudio;
                    }
                    else
                    {
                        // Output the one message
                        audiostring += modeAudio + stateAudio;
                    }
    
                    if ((int)state.status == (int)MAV_STATE_CRITICAL || state.status == (int)MAV_STATE_EMERGENCY)
    
    pixhawk's avatar
    pixhawk committed
                    {
                        GAudioOutput::instance()->startEmergency();
                    }
                    else if (modechanged || statechanged)
                    {
                        GAudioOutput::instance()->stopEmergency();
                        GAudioOutput::instance()->say(audiostring);
                    }
    
    pixhawk's avatar
    pixhawk committed
                }
                break;
            case MAVLINK_MSG_ID_RAW_IMU:
    
    pixhawk's avatar
    pixhawk committed
                {
    
    pixhawk's avatar
    pixhawk committed
                    mavlink_raw_imu_t raw;
                    mavlink_msg_raw_imu_decode(&message, &raw);
    
                    quint64 time = getUnixTime(raw.usec);
    
    pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
                    emit valueChanged(uasId, "Accel. X", raw.xacc, time);
                    emit valueChanged(uasId, "Accel. Y", raw.yacc, time);
                    emit valueChanged(uasId, "Accel. Z", raw.zacc, time);
                    emit valueChanged(uasId, "Gyro Phi", raw.xgyro, time);
                    emit valueChanged(uasId, "Gyro Theta", raw.ygyro, time);
                    emit valueChanged(uasId, "Gyro Psi", raw.zgyro, time);
                    emit valueChanged(uasId, "Mag. X", raw.xmag, time);
                    emit valueChanged(uasId, "Mag. Y", raw.ymag, time);
                    emit valueChanged(uasId, "Mag. Z", raw.zmag, time);
    
    pixhawk's avatar
    pixhawk committed
                }
                break;
            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;
    
    pixhawk's avatar
    pixhawk committed
                {
    
    pixhawk's avatar
    pixhawk committed
                    mavlink_attitude_t attitude;
                    mavlink_msg_attitude_decode(&message, &attitude);
    
    lm's avatar
    lm committed
                    roll = attitude.roll;
                    pitch = attitude.pitch;
                    yaw = attitude.yaw;
    
    pixhawk's avatar
    pixhawk committed
                    emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
                    emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
                    emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
                    emit valueChanged(this, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
                    emit valueChanged(this, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
                    emit valueChanged(this, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
    
    lm's avatar
    lm committed
                    emit valueChanged(uasId, "rollspeed IMU", attitude.rollspeed, time);
                    emit valueChanged(uasId, "pitchspeed IMU", attitude.pitchspeed, time);
                    emit valueChanged(uasId, "yawspeed IMU", attitude.yawspeed, time);
    
    pixhawk's avatar
    pixhawk committed
                    emit attitudeChanged(this, mavlink_msg_attitude_get_roll(&message), mavlink_msg_attitude_get_pitch(&message), mavlink_msg_attitude_get_yaw(&message), time);
    
    pixhawk's avatar
    pixhawk committed
                }
                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.usec);
    
    lm's avatar
    lm committed
                    localX = pos.x;
                    localY = pos.y;
                    localZ = pos.z;
    
    lm's avatar
    lm committed
                    emit valueChanged(uasId, "x", pos.x, time);
                    emit valueChanged(uasId, "y", pos.y, time);
                    emit valueChanged(uasId, "z", pos.z, time);
    
                    emit valueChanged(uasId, "Vx", pos.vx, time);
                    emit valueChanged(uasId, "Vy", pos.vy, time);
                    emit valueChanged(uasId, "Vz", pos.vz, time);
    
    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);
                    //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
    
    pixhawk's avatar
    pixhawk committed
                    // Set internal state
                    if (!positionLock)
                    {
                        // If position was not locked before, notify positive
                        GAudioOutput::instance()->notifyPositive();
                    }
                    positionLock = true;
    
    lm's avatar
    lm committed
                }
                break;
    
            case MAVLINK_MSG_ID_GLOBAL_POSITION:
                //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_t pos;
                    mavlink_msg_global_position_decode(&message, &pos);
                    quint64 time = getUnixTime(pos.usec);
                    emit valueChanged(uasId, "lat", pos.lat, time);
                    emit valueChanged(uasId, "lon", pos.lon, time);
                    emit valueChanged(uasId, "alt", pos.alt, time);
                    emit valueChanged(uasId, "g-vx", pos.vx, time);
                    emit valueChanged(uasId, "g-vy", pos.vy, time);
                    emit valueChanged(uasId, "g-vz", pos.vz, time);
                    emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
    
    pixhawk's avatar
    pixhawk committed
                    emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
                    // Set internal state
                    if (!positionLock)
                    {
                        // If position was not locked before, notify positive
                        GAudioOutput::instance()->notifyPositive();
                    }
                    positionLock = true;
    
                }
                break;
            case MAVLINK_MSG_ID_GPS_RAW:
                //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_gps_raw_t pos;
                    mavlink_msg_gps_raw_decode(&message, &pos);
    
    
                    // SANITY CHECK
                    // only accept values in a realistic range
    
    pixhawk's avatar
    pixhawk committed
                   // quint64 time = getUnixTime(pos.usec);
                    quint64 time = MG::TIME::getGroundTimeNow();
    
                    emit valueChanged(uasId, "lat", pos.lat, time);
                    emit valueChanged(uasId, "lon", pos.lon, time);
    
    lm's avatar
    lm committed
                    if (pos.fix_type > 0)
    
    Laurens Mackay's avatar
    Laurens Mackay committed
                        emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
    
    lm's avatar
    lm committed
    
                        // 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, "alt", pos.alt, time);
                        // Smaller than threshold and not NaN
                        if (pos.v < 1000000 && pos.v == pos.v)
                        {
                            emit valueChanged(uasId, "speed", pos.v, 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(pos.v));
                        }
    
    lm's avatar
    lm committed
            case MAVLINK_MSG_ID_GPS_STATUS:
                {
                    mavlink_gps_status_t pos;
                    mavlink_msg_gps_status_decode(&message, &pos);
    
    lm's avatar
    lm committed
                    for(int i = 0; i < (int)pos.satellites_visible; i++)
    
    lm's avatar
    lm committed
                    {
    
    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_RC_CHANNELS_RAW:
    
                    mavlink_rc_channels_raw_t channels;
                    mavlink_msg_rc_channels_raw_decode(&message, &channels);
    
    pixhawk's avatar
    pixhawk committed
                    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);
                }
                break;
            case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
                {
                    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;
    
            case MAVLINK_MSG_ID_PARAM_VALUE:
                {
                    mavlink_param_value_t value;
                    mavlink_msg_param_value_decode(&message, &value);
                    emit parameterChanged(uasId, message.compid, QString((char*)value.param_id), value.param_value);
                }
                break;
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_DEBUG:
    
    pixhawk's avatar
    pixhawk committed
                emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
    
    pixhawk's avatar
    pixhawk committed
                break;
    
            case MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT:
                {
                    mavlink_attitude_controller_output_t out;
                    mavlink_msg_attitude_controller_output_decode(&message, &out);
                    quint64 time = MG::TIME::getGroundTimeNowUsecs();
    
    lm's avatar
    lm committed
                    emit attitudeThrustSetPointChanged(this, out.roll/127.0f, out.pitch/127.0f, out.yaw/127.0f, (uint8_t)out.thrust, time);
    
                    emit valueChanged(uasId, "att control roll", out.roll, time/1000.0f);
                    emit valueChanged(uasId, "att control pitch", out.pitch, time/1000.0f);
                    emit valueChanged(uasId, "att control yaw", out.yaw, time/1000.0f);
                }
                break;
            case MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT:
                {
                    mavlink_position_controller_output_t out;
                    mavlink_msg_position_controller_output_decode(&message, &out);
    
    pixhawk's avatar
    pixhawk committed
                    quint64 time = MG::TIME::getGroundTimeNow();
    
                    //emit positionSetPointsChanged(uasId, out.x/127.0f, out.y/127.0f, out.z/127.0f, out.yaw, time);
    
    pixhawk's avatar
    pixhawk committed
                    emit valueChanged(uasId, "pos control x", out.x, time);
                    emit valueChanged(uasId, "pos control y", out.y, time);
                    emit valueChanged(uasId, "pos control z", out.z, time);
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_WAYPOINT_COUNT:
                {
                    mavlink_waypoint_count_t wpc;
                    mavlink_msg_waypoint_count_decode(&message, &wpc);
    
    pixhawk's avatar
    pixhawk committed
                    if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
                    {
                        waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
                    }
    
    pixhawk's avatar
    pixhawk committed
                }
                break;
    
    
                    mavlink_waypoint_t wp;
                    mavlink_msg_waypoint_decode(&message, &wp);
    
    pixhawk's avatar
    pixhawk committed
                    //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
    
    pixhawk's avatar
    pixhawk committed
                    if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
                    {
                        waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
                    }
    
    pixhawk's avatar
    pixhawk committed
                break;
    
    pixhawk's avatar
    pixhawk committed
    
    
            case MAVLINK_MSG_ID_WAYPOINT_ACK:
                {
                    mavlink_waypoint_ack_t wpa;
                    mavlink_msg_waypoint_ack_decode(&message, &wpa);
                    if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
                    {
                        waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
                    }
                }
                break;
    
    
    pixhawk's avatar
    pixhawk committed
            case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
                {
                    mavlink_waypoint_request_t wpr;
                    mavlink_msg_waypoint_request_decode(&message, &wpr);
    
    pixhawk's avatar
    pixhawk committed
                    if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
                    {
                        waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
                    }
    
    pixhawk's avatar
    pixhawk committed
                }
                break;
    
    
            case MAVLINK_MSG_ID_WAYPOINT_REACHED:
    
    pixhawk's avatar
    pixhawk committed
                    mavlink_waypoint_reached_t wpr;
                    mavlink_msg_waypoint_reached_decode(&message, &wpr);
                    waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
    
    pixhawk's avatar
    pixhawk committed
                break;
    
    pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
                {
    
                    mavlink_waypoint_current_t wpc;
                    mavlink_msg_waypoint_current_decode(&message, &wpc);
                    waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
    
    pixhawk's avatar
    pixhawk committed
                break;
    
    pixhawk's avatar
    pixhawk committed
    
    
            case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT:
                {
                    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;
    
    pixhawk's avatar
    pixhawk committed
    
    
    lm's avatar
    lm committed
                {
                    QByteArray b;
                    b.resize(256);
    
    pixhawk's avatar
    pixhawk committed
                    mavlink_msg_statustext_get_text(&message, (int8_t*)b.data());
    
    lm's avatar
    lm committed
                    //b.append('\0');
                    QString text = QString(b);
    
    pixhawk's avatar
    pixhawk committed
                    int severity = mavlink_msg_statustext_get_severity(&message);
    
                    //qDebug() << "RECEIVED STATUS:" << text;false
    
    lm's avatar
    lm committed
                    //emit statusTextReceived(severity, text);
    
                    emit textMessageReceived(uasId, message.compid, severity, text);
    
    lm's avatar
    lm committed
                }
                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:
                {
                    mavlink_nav_filter_bias_t bias;
                    mavlink_msg_nav_filter_bias_decode(&message, &bias);
                    quint64 time = MG::TIME::getGroundTimeNow();
                    emit valueChanged(uasId, "b_f[0]", bias.accel_0, time);
                    emit valueChanged(uasId, "b_f[1]", bias.accel_1, time);
                    emit valueChanged(uasId, "b_f[2]", bias.accel_2, time);
                    emit valueChanged(uasId, "b_w[0]", bias.gyro_0, time);
                    emit valueChanged(uasId, "b_w[1]", bias.gyro_1, time);
                    emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
                }
                break;
    
           case MAVLINK_MSG_ID_RADIO_CALIBRATION:
                {
                    mavlink_radio_calibration_t radioMsg;
                    mavlink_msg_radio_calibration_decode(&message, &radioMsg);
                    QVector<float> aileron;
                    QVector<float> elevator;
                    QVector<float> rudder;
                    QVector<float> gyro;
                    QVector<float> pitch;
                    QVector<float> throttle;
    
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
                        aileron << radioMsg.aileron[i];
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
                        elevator << radioMsg.elevator[i];
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
                        rudder << radioMsg.rudder[i];
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
                        gyro << radioMsg.gyro[i];
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
                        pitch << radioMsg.pitch[i];
                    for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
                        throttle << radioMsg.throttle[i];
    
                    QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron,
                                                                                        elevator,
                                                                                        rudder,
                                                                                        gyro,
                                                                                        pitch,
                                                                                        throttle);
                    emit radioCalibrationReceived(radioData);
                    delete radioData;
                }
                break;
    
    
    pixhawk's avatar
    pixhawk committed
            default:
    
    lm's avatar
    lm committed
                {
                    if (!unknownPackets.contains(message.msgid))
                    {
                        unknownPackets.append(message.msgid);
    
                        //GAudioOutput::instance()->say("UNABLE TO DECODE MESSAGE WITH ID " + QString::number(message.msgid) + " FROM SYSTEM " + QString::number(message.sysid));
                        std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
    
    lm's avatar
    lm committed
                        //qDebug() << std::cerr << "Unable to decode message from system " << std::dec << static_cast<int>(message.acid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
                    }
                }
    
    pixhawk's avatar
    pixhawk committed
                break;
            }
        }
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
    {
    
    lm's avatar
    lm committed
      #ifdef MAVLINK_ENABLED_PIXHAWK
    
    pixhawk's avatar
    pixhawk committed
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
    pixhawk's avatar
    pixhawk committed
      mavlink_message_t msg;
      mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
      sendMessage(msg);
    #endif
    }
    
    void UAS::startRadioControlCalibration()
    {
      mavlink_message_t msg;
      mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_RC);
      sendMessage(msg);
    }
    
    
    lm's avatar
    lm committed
    void UAS::startDataRecording()
    {
      mavlink_message_t msg;
      mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_START);
      sendMessage(msg);
    }
    
    void UAS::pauseDataRecording()
    {
      mavlink_message_t msg;
      mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_PAUSE);
      sendMessage(msg);
    }
    
    void UAS::stopDataRecording()
    {
      mavlink_message_t msg;
      mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_REC_STOP);
      sendMessage(msg);
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::startMagnetometerCalibration()
    {
        mavlink_message_t msg;
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_MAG);
        sendMessage(msg);
    }
    
    void UAS::startGyroscopeCalibration()
    {
        mavlink_message_t msg;
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_GYRO);
        sendMessage(msg);
    }
    
    void UAS::startPressureCalibration()
    {
        mavlink_message_t msg;
        mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_IMU, MAV_ACTION_CALIBRATE_PRESSURE);
        sendMessage(msg);
    }
    
    
    quint64 UAS::getUnixTime(quint64 time)
    {
        if (time == 0)
        {
            return MG::TIME::getGroundTimeNow();
        }
        // 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
    
        else if (time < 1261440000000000LLU)
    
                onboardTimeOffset = MG::TIME::getGroundTimeNow() - 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.
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setMode(int mode)
    
    pixhawk's avatar
    pixhawk committed
    {
    
    lm's avatar
    lm committed
        if ((uint8_t)mode >= MAV_MODE_LOCKED && (uint8_t)mode <= MAV_MODE_RC_TRAINING)
    
    pixhawk's avatar
    pixhawk committed
        {
            mavlink_message_t msg;
    
    lm's avatar
    lm committed
            mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, (uint8_t)uasId, (uint8_t)mode);
    
    pixhawk's avatar
    pixhawk committed
            sendMessage(msg);
    
    lm's avatar
    lm committed
            qDebug() << "SENDING REQUEST TO SET MODE TO SYSTEM" << uasId << ", REQUEST TO SET MODE " << (uint8_t)mode;
    
    pixhawk's avatar
    pixhawk committed
        }
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::sendMessage(mavlink_message_t message)
    {
        // Emit message on all links that are currently connected
        QList<LinkInterface*>::iterator i;
        for (i = links->begin(); i != links->end(); ++i)
        {
            sendMessage(*i, message);
        }
    }
    
    void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
    {
        // Create buffer
        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
        // Write message into buffer, prepending start sign
    
    pixhawk's avatar
    pixhawk committed
        int len = mavlink_msg_to_send_buffer(buffer, &message);
    
    pixhawk's avatar
    pixhawk committed
        // If link is connected
        if (link->isConnected())
        {
            // Send the portion of the buffer now occupied by the message
            link->writeBytes((const char*)buffer, len);
        }
    }
    
    /**
     * @param value battery voltage
     */
    
    float UAS::filterVoltage(float value) const
    
    pixhawk's avatar
    pixhawk committed
    {
    
        return lpVoltage * 0.7f + value * 0.3f;
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
    {
        switch (statusCode)
        {
    
    lm's avatar
    lm committed
        case MAV_STATE_UNINIT:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("UNINIT");
            stateDescription = tr("Not initialized");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_BOOT:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("BOOT");
            stateDescription = tr("Booting system, please wait..");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_CALIBRATING:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("CALIBRATING");
            stateDescription = tr("Calibrating sensors..");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_ACTIVE:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("ACTIVE");
            stateDescription = tr("Normal operation mode");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_STANDBY:
            uasState = tr("STANDBY");
            stateDescription = tr("Standby, operational");
            break;
        case MAV_STATE_CRITICAL:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("CRITICAL");
            stateDescription = tr("Failure occured!");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_EMERGENCY:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("EMERGENCY");
            stateDescription = tr("EMERGENCY: Please land");
            break;
    
    lm's avatar
    lm committed
        case MAV_STATE_POWEROFF:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("SHUTDOWN");
            stateDescription = tr("Powering off system");
            break;
    
    lm's avatar
    lm committed
        default:
    
    pixhawk's avatar
    pixhawk committed
            uasState = tr("UNKNOWN");
            stateDescription = tr("FAILURE: Unknown system state");
            break;
        }
    }
    
    
    
    /* MANAGEMENT */
    
    /*
     *
     * @return The uptime in milliseconds
     *
     **/
    
    pixhawk's avatar
    pixhawk committed
    {
        if(startTime == 0) {
            return 0;
        } else {
            return MG::TIME::getGroundTimeNow() - startTime;
        }
    }
    
    
    int UAS::getCommunicationStatus() const
    
    pixhawk's avatar
    pixhawk committed
    {
        return commStatus;
    }
    
    
    void UAS::requestParameters()
    {
        mavlink_message_t msg;
    
        mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 25);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    void UAS::writeParametersToStorage()
    
        mavlink_message_t msg;
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE);
    
    unknown's avatar
    unknown committed
        //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
    
        sendMessage(msg);
    }
    
    void UAS::readParametersFromStorage()
    {
        mavlink_message_t msg;
        // TODO Replace MG System ID with static function call and allow to change ID in GUI
        mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(uint8_t)MAV_ACTION_STORAGE_READ);
        sendMessage(msg);
    
    lm's avatar
    lm committed
    }
    
    void UAS::enableAllDataTransmission(bool enabled)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
    lm's avatar
    lm committed
        // Buffers to write data to
    
        mavlink_request_data_stream_t stream;
    
    lm's avatar
    lm committed
        // Select the message to request from now on
        // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
    
    lm's avatar
    lm committed
        // Select the update rate in Hz the message should be send
        // All messages will be send with their default rate
        stream.req_message_rate = 0;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
    
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    lm's avatar
    lm committed
        sendMessage(msg);
    
    lm's avatar
    lm committed
    }
    
    void UAS::enableRawSensorDataTransmission(bool enabled)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
    lm's avatar
    lm committed
        // Buffers to write data to
        mavlink_message_t msg;
    
        mavlink_request_data_stream_t stream;
    
    lm's avatar
    lm committed
        // Select the message to request from now on
    
    lm's avatar
    lm committed
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
    
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    lm's avatar
    lm committed
        sendMessage(msg);
    
    lm's avatar
    lm committed
    }
    
    void UAS::enableExtendedSystemStatusTransmission(bool enabled)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 2;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 10;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    lm's avatar
    lm committed
    }
    
    lm's avatar
    lm committed
    void UAS::enableRCChannelDataTransmission(bool enabled)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 3;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    #elif defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
        mavlink_message_t msg;
        mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
        sendMessage(msg);
    
    lm's avatar
    lm committed
    }
    
    void UAS::enableRawControllerDataTransmission(bool enabled)
    {
    
    lm's avatar
    lm committed
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 4;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);