Skip to content
Snippets Groups Projects
UAS.cc 129 KiB
Newer Older
  • Learn to ignore specific revisions
  •             sendMessage(link, message);
    
                qDebug() << "SENT MESSAGE id" << message.msgid << "component" << message.compid;
    
            }
            else
            {
                // Remove from list
                links->removeAt(links->indexOf(link));
            }
        }
    }
    
    /**
    * Forward a message to all links that are currently connected.
    * @param message that is to be forwarded
    */
    void UAS::forwardMessage(mavlink_message_t message)
    {
        // Emit message on all links that are currently connected
        QList<LinkInterface*>link_list = LinkManager::instance()->getLinksForProtocol(mavlink);
    
        foreach(LinkInterface* link, link_list)
        {
            if (link)
            {
                SerialLink* serial = dynamic_cast<SerialLink*>(link);
                if(serial != 0)
                {
                    for(int i=0; i<links->size(); i++)
                    {
                        if(serial != links->at(i))
                        {
                            qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
                            sendMessage(serial, message);
                        }
                    }
                }
            }
        }
    }
    
    /**
    * Send a message to the link that is connected.
    * @param link that the message will be sent to
    * @message that is to be sent
    */
    void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
    {
        if(!link) return;
        // Create buffer
        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
        // Write message into buffer, prepending start sign
        int len = mavlink_msg_to_send_buffer(buffer, &message);
        static uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS;
        mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getId(), message.len, messageKeys[message.msgid]);
    
        // If link is connected
        if (link->isConnected())
        {
            // Send the portion of the buffer now occupied by the message
            link->writeBytes((const char*)buffer, len);
        }
    
        else
        {
            qDebug() << "LINK NOT CONNECTED, NOT SENDING!";
        }
    
    }
    
    /**
     * @param value battery voltage
     */
    float UAS::filterVoltage(float value) const
    {
        return lpVoltage * 0.7f + value * 0.3f;
    }
    
    /**
    * The mode can be preflight or unknown.
    * @Return the mode of the autopilot
    */
    QString UAS::getNavModeText(int mode)
    {
        if (autopilot == MAV_AUTOPILOT_PIXHAWK)
        {
            switch (mode)
            {
            case 0:
                return QString("PREFLIGHT");
                break;
            default:
                return QString("UNKNOWN");
            }
        }
        else if (autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA)
        {
            return QString("UNKNOWN");
        }
        else if (autopilot == MAV_AUTOPILOT_OPENPILOT)
        {
            return QString("UNKNOWN");
        }
        // If nothing matches, return unknown
        return QString("UNKNOWN");
    }
    
    
    * Get the status of the code and a description of the status.
    * Status can be unitialized, booting up, calibrating sensors, active
    * standby, cirtical, emergency, shutdown or unknown.
    */
    void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
    {
        switch (statusCode)
        {
        case MAV_STATE_UNINIT:
            uasState = tr("UNINIT");
            stateDescription = tr("Unitialized, booting up.");
            break;
        case MAV_STATE_BOOT:
            uasState = tr("BOOT");
            stateDescription = tr("Booting system, please wait.");
            break;
        case MAV_STATE_CALIBRATING:
            uasState = tr("CALIBRATING");
            stateDescription = tr("Calibrating sensors, please wait.");
            break;
        case MAV_STATE_ACTIVE:
            uasState = tr("ACTIVE");
            stateDescription = tr("Active, normal operation.");
            break;
        case MAV_STATE_STANDBY:
            uasState = tr("STANDBY");
            stateDescription = tr("Standby mode, ready for launch.");
            break;
        case MAV_STATE_CRITICAL:
            uasState = tr("CRITICAL");
            stateDescription = tr("FAILURE: Continuing operation.");
            break;
        case MAV_STATE_EMERGENCY:
            uasState = tr("EMERGENCY");
            stateDescription = tr("EMERGENCY: Land Immediately!");
            break;
            //case MAV_STATE_HILSIM:
            //uasState = tr("HIL SIM");
            //stateDescription = tr("HIL Simulation, Sensors read from SIM");
            //break;
    
        case MAV_STATE_POWEROFF:
            uasState = tr("SHUTDOWN");
            stateDescription = tr("Powering off system.");
            break;
    
        default:
            uasState = tr("UNKNOWN");
            stateDescription = tr("Unknown system state");
            break;
        }
    }
    
    QImage UAS::getImage()
    {
    #ifdef MAVLINK_ENABLED_PIXHAWK
    
    //    qDebug() << "IMAGE TYPE:" << imageType;
    
        // RAW greyscale
        if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
        {
    
            int imgColors = 255;
    
    
            // Construct PGM header
            QString header("P5\n%1 %2\n%3\n");
            header = header.arg(imageWidth).arg(imageHeight).arg(imgColors);
    
    
            QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size() - 1);
    
            tmpImage.append(imageRecBuffer);
    
            //qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
    
            if (imageRecBuffer.isNull())
            {
                qDebug()<< "could not convertToPGM()";
                return QImage();
            }
    
            if (!image.loadFromData(tmpImage, "PGM"))
            {
    
                qDebug()<< __FILE__ << __LINE__ << "could not create extracted image";
    
                return QImage();
            }
    
        }
        // BMP with header
        else if (imageType == MAVLINK_DATA_STREAM_IMG_BMP ||
                 imageType == MAVLINK_DATA_STREAM_IMG_JPEG ||
                 imageType == MAVLINK_DATA_STREAM_IMG_PGM ||
                 imageType == MAVLINK_DATA_STREAM_IMG_PNG)
        {
            if (!image.loadFromData(imageRecBuffer))
            {
    
                qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!";
    
            }
        }
        // Restart statemachine
        imagePacketsArrived = 0;
        //imageRecBuffer.clear();
        return image;
    #else
        return QImage();
    #endif
    
    }
    
    void UAS::requestImage()
    {
    #ifdef MAVLINK_ENABLED_PIXHAWK
        qDebug() << "trying to get an image from the uas...";
    
        // check if there is already an image transmission going on
        if (imagePacketsArrived == 0)
        {
            mavlink_message_t msg;
            mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
            sendMessage(msg);
        }
    #endif
    }
    
    
    /* MANAGEMENT */
    
    /**
     *
     * @return The uptime in milliseconds
     *
     */
    quint64 UAS::getUptime() const
    {
        if(startTime == 0)
        {
            return 0;
        }
        else
        {
            return QGC::groundTimeMilliseconds() - startTime;
        }
    }
    
    int UAS::getCommunicationStatus() const
    {
        return commStatus;
    }
    
    void UAS::requestParameters()
    {
        mavlink_message_t msg;
        mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_ALL);
        sendMessage(msg);
    
        qDebug() << __FILE__ << ":" << __LINE__ << "LOADING PARAM LIST";
    
    }
    
    void UAS::writeParametersToStorage()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
        qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
        sendMessage(msg);
    }
    
    void UAS::readParametersFromStorage()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 0, -1, -1, -1, 0, 0, 0);
        sendMessage(msg);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableAllDataTransmission(int rate)
    {
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        // 0 is a magic ID and will enable/disable the standard message set except for heartbeat
        stream.req_stream_id = MAV_DATA_STREAM_ALL;
        // Select the update rate in Hz the message should be send
        // All messages will be send with their default rate
        // TODO: use 0 to turn off and get rid of enable/disable? will require
        //  a different magic flag for turning on defaults, possibly something really high like 1111 ?
        stream.req_message_rate = 0;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableRawSensorDataTransmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_RAW_SENSORS;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableExtendedSystemStatusTransmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_EXTENDED_STATUS;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableRCChannelDataTransmission(int rate)
    {
    #if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
        mavlink_message_t msg;
        mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
        sendMessage(msg);
    #else
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    #endif
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableRawControllerDataTransmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_RAW_CONTROLLER;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    }
    
    //void UAS::enableRawSensorFusionTransmission(int rate)
    //{
    //    // 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 = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
    //    // Select the update rate in Hz the message should be send
    //    stream.req_message_rate = rate;
    //    // Start / stop the message
    //    stream.start_stop = (rate) ? 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);
    //    sendMessage(msg);
    //}
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enablePositionTransmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_POSITION;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableExtra1Transmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_EXTRA1;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
        sendMessage(msg);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableExtra2Transmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_EXTRA2;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
        sendMessage(msg);
    }
    
    
    * @param rate The update rate in Hz the message should be sent
    */
    void UAS::enableExtra3Transmission(int rate)
    {
        // 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 = MAV_DATA_STREAM_EXTRA3;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = rate;
        // Start / stop the message
        stream.start_stop = (rate) ? 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);
        sendMessage(msg);
    }
    
    /**
     * Set a parameter value onboard
     *
     * @param component The component to set the parameter
    
     */
    void UAS::setParameter(const int component, const QString& id, const QVariant& value)
    {
        if (!id.isNull())
        {
            mavlink_message_t msg;
            mavlink_param_set_t p;
            mavlink_param_union_t union_value;
    
            // Assign correct value based on QVariant
    
            // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
    
            if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
    
                switch (value.type())
                {
                case QVariant::Char:
                    union_value.param_float = (unsigned char)value.toChar().toAscii();
                    p.param_type = MAV_PARAM_TYPE_INT8;
                    break;
                case QVariant::Int:
                    union_value.param_float = value.toInt();
                    p.param_type = MAV_PARAM_TYPE_INT32;
                    break;
                case QVariant::UInt:
                    union_value.param_float = value.toUInt();
                    p.param_type = MAV_PARAM_TYPE_UINT32;
                    break;
                case QMetaType::Float:
                    union_value.param_float = value.toFloat();
                    p.param_type = MAV_PARAM_TYPE_REAL32;
                    break;
                default:
                    qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
                    return;
                }
            }
            else
            {
                switch (value.type())
                {
                case QVariant::Char:
                    union_value.param_int8 = (unsigned char)value.toChar().toAscii();
                    p.param_type = MAV_PARAM_TYPE_INT8;
                    break;
                case QVariant::Int:
                    union_value.param_int32 = value.toInt();
                    p.param_type = MAV_PARAM_TYPE_INT32;
                    break;
                case QVariant::UInt:
                    union_value.param_uint32 = value.toUInt();
                    p.param_type = MAV_PARAM_TYPE_UINT32;
                    break;
                case QMetaType::Float:
                    union_value.param_float = value.toFloat();
                    p.param_type = MAV_PARAM_TYPE_REAL32;
                    break;
                default:
                    qCritical() << "ABORTED PARAM SEND, NO VALID QVARIANT TYPE";
                    return;
                }
    
            }
    
            p.param_value = union_value.param_float;
            p.target_system = (uint8_t)uasId;
            p.target_component = (uint8_t)component;
    
            //qDebug() << "SENT PARAM:" << value;
    
            // Copy string into buffer, ensuring not to exceed the buffer size
            for (unsigned int i = 0; i < sizeof(p.param_id); i++)
            {
                // String characters
                if ((int)i < id.length())
                {
                    p.param_id[i] = id.toAscii()[i];
                }
                else
                {
                    // Fill rest with zeros
                    p.param_id[i] = 0;
                }
            }
            mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
            sendMessage(msg);
        }
    }
    
    
    * Request parameter, use parameter name to request it.
    */
    void UAS::requestParameter(int component, int id)
    {
        // Request parameter, use parameter name to request it
        mavlink_message_t msg;
        mavlink_param_request_read_t read;
        read.param_index = id;
        read.param_id[0] = '\0'; // Enforce null termination
        read.target_system = uasId;
        read.target_component = component;
        mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
        sendMessage(msg);
        //qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
    }
    
    /**
    * Request a parameter, use parameter name to request it.
    */
    void UAS::requestParameter(int component, const QString& parameter)
    {
        // Request parameter, use parameter name to request it
        mavlink_message_t msg;
        mavlink_param_request_read_t read;
        read.param_index = -1;
        // Copy full param name or maximum max field size
        if (parameter.length() > MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN)
        {
            emit textMessageReceived(uasId, 0, 255, QString("QGC WARNING: Parameter name %1 is more than %2 bytes long. This might lead to errors and mishaps!").arg(parameter).arg(MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN-1));
        }
        memcpy(read.param_id, parameter.toStdString().c_str(), qMax(parameter.length(), MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN));
        read.param_id[15] = '\0'; // Enforce null termination
        read.target_system = uasId;
        read.target_component = component;
        mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
        sendMessage(msg);
        qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
    }
    
    /**
    * @param systemType Type of MAV.
    */
    void UAS::setSystemType(int systemType)
    {
        if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END))
        {
          type = systemType;
    
          // If the airframe is still generic, change it to a close default type
          if (airframe == 0)
          {
              switch (systemType)
              {
              case MAV_TYPE_FIXED_WING:
                  airframe = QGC_AIRFRAME_EASYSTAR;
                  break;
              case MAV_TYPE_QUADROTOR:
                  airframe = QGC_AIRFRAME_MIKROKOPTER;
                  break;
              }
          }
          emit systemSpecsChanged(uasId);
       }
    }
    
    void UAS::setUASName(const QString& name)
    {
        if (name != "")
        {
            this->name = name;
            writeSettings();
            emit nameChanged(name);
            emit systemSpecsChanged(uasId);
        }
    }
    
    void UAS::executeCommand(MAV_CMD command)
    {
        mavlink_message_t msg;
        mavlink_command_long_t cmd;
        cmd.command = (uint16_t)command;
        cmd.confirmation = 0;
        cmd.param1 = 0.0f;
        cmd.param2 = 0.0f;
        cmd.param3 = 0.0f;
        cmd.param4 = 0.0f;
        cmd.param5 = 0.0f;
        cmd.param6 = 0.0f;
        cmd.param7 = 0.0f;
        cmd.target_system = uasId;
        cmd.target_component = 0;
        mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
        sendMessage(msg);
    }
    
    void UAS::executeCommandAck(int num, bool success)
    {
        mavlink_message_t msg;
        mavlink_command_ack_t ack;
        ack.command = num;
        ack.result = (success ? 1 : 0);
        mavlink_msg_command_ack_encode(mavlink->getSystemId(),mavlink->getComponentId(),&msg,&ack);
        sendMessage(msg);
    }
    
    
    void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component)
    {
        mavlink_message_t msg;
        mavlink_command_long_t cmd;
        cmd.command = (uint16_t)command;
        cmd.confirmation = confirmation;
        cmd.param1 = param1;
        cmd.param2 = param2;
        cmd.param3 = param3;
        cmd.param4 = param4;
        cmd.param5 = param5;
        cmd.param6 = param6;
        cmd.param7 = param7;
        cmd.target_system = uasId;
        cmd.target_component = component;
        mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
        sendMessage(msg);
    }
    
    /**
     * Launches the system
     *
     */
    void UAS::launch()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    /**
     * @warning Depending on the UAS, this might make the rotors of a helicopter spinning
     *
     */
    void UAS::armSystem()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_SAFETY_ARMED, navMode);
        sendMessage(msg);
    }
    
    /**
     * @warning Depending on the UAS, this might completely stop all motors.
     *
     */
    void UAS::disarmSystem()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_SAFETY_ARMED, navMode);
        sendMessage(msg);
    }
    
    
    void UAS::toggleArmedState()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode ^ MAV_MODE_FLAG_SAFETY_ARMED, navMode);
        sendMessage(msg);
    }
    
    
    void UAS::goAutonomous()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & MAV_MODE_FLAG_AUTO_ENABLED & ~MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode);
        sendMessage(msg);
    }
    
    void UAS::goManual()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_AUTO_ENABLED & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode);
        sendMessage(msg);
    }
    
    void UAS::toggleAutonomy()
    {
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode ^ MAV_MODE_FLAG_AUTO_ENABLED ^ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode);
        sendMessage(msg);
    }
    
    
    * This can only be done if the system has manual inputs enabled and is armed.
    */
    void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons)
    {
    
        // Scale values
        double rollPitchScaling = 1.0f * 1000.0f;
        double yawScaling = 1.0f * 1000.0f;
        double thrustScaling = 1.0f * 1000.0f;
    
        manualRollAngle = roll * rollPitchScaling;
        manualPitchAngle = pitch * rollPitchScaling;
        manualYawAngle = yaw * yawScaling;
        manualThrust = thrust * thrustScaling;
    
        // If system has manual inputs enabled and is armed
        if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED))
        {
            mavlink_message_t message;
            mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)manualPitchAngle, (float)manualRollAngle, (float)manualThrust, (float)manualYawAngle, buttons);
            sendMessage(message);
            //qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
    
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
        }
        else
        {
    
            //qDebug() << "JOYSTICK/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send joystick commands first";
    
        }
    }
    
    void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
    {
    
        // If system has manual inputs enabled and is armed
        if(((mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (mode & MAV_MODE_FLAG_HIL_ENABLED))
        {
            mavlink_message_t message;
            mavlink_msg_setpoint_6dof_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, (float)x, (float)y, (float)z, (float)roll, (float)pitch, (float)yaw);
            sendMessage(message);
            qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGE: x" << x << " y: " << y << " z: " << z << " roll: " << roll << " pitch: " << pitch << " yaw: " << yaw;
    
            //emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
        }
        else
        {
            qDebug() << "3DMOUSE/MANUAL CONTROL: IGNORING COMMANDS: Set mode to MANUAL to send 3DMouse commands first";
        }
    
    }
    
    /**
    * @return the type of the system
    */
    int UAS::getSystemType()
    {
        return this->type;
    }
    
    /**
    * Halt the uas.
    */
    void UAS::halt()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    /**
    * Make the UAS move.
    */
    void UAS::go()
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    
    */
    void UAS::home()
    {
        mavlink_message_t msg;
    
        double latitude = UASManager::instance()->getHomeLatitude();
        double longitude = UASManager::instance()->getHomeLongitude();
        double altitude = UASManager::instance()->getHomeAltitude();
        int frame = UASManager::instance()->getHomeFrame();
    
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude);
        sendMessage(msg);
    }
    
    /**
    
    * Order the robot to land on the runway
    
    */
    void UAS::land()
    {
        mavlink_message_t msg;
    
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0);
        sendMessage(msg);
    }
    
    /**
     * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
     * and might differ between systems.
     */
    void UAS::emergencySTOP()
    {
        // FIXME MAVLINKV10PORTINGNEEDED
        halt();
    }
    
    /**
     * Shut down this mav - All onboard systems are immediately shut down (e.g. the
     *  main power line is cut).
     * @warning This might lead to a crash.
     *
     * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
     */
    bool UAS::emergencyKILL()
    {
        halt();
        // FIXME MAVLINKV10PORTINGNEEDED
        //    bool result = false;
        //    QMessageBox msgBox;
        //    msgBox.setIcon(QMessageBox::Critical);
        //    msgBox.setText("EMERGENCY: KILL ALL MOTORS ON UAS");
        //    msgBox.setInformativeText("Do you want to cut power on all systems?");
        //    msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
        //    msgBox.setDefaultButton(QMessageBox::Cancel);
        //    int ret = msgBox.exec();
    
        //    // Close the message box shortly after the click to prevent accidental clicks
        //    QTimer::singleShot(5000, &msgBox, SLOT(reject()));
    
    
        //    if (ret == QMessageBox::Yes)
        //    {
        //        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, (int)MAV_ACTION_EMCY_KILL);
        //        // Send message twice to increase chance of reception
        //        sendMessage(msg);
        //        sendMessage(msg);
        //        result = true;
        //    }
        //    return result;
        return false;
    }
    
    /**
    * If enabled, connect the flight gear link.
    */
    void UAS::enableHilFlightGear(bool enable, QString options)
    {
        QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
        if (!link || !simulation) {
            // Delete wrong sim
            if (simulation) {
                stopHil();
                delete simulation;
            }
            simulation = new QGCFlightGearLink(this, options);
        }
        // Connect Flight Gear Link
        link = dynamic_cast<QGCFlightGearLink*>(simulation);
        link->setStartupArguments(options);
    
        if (enable)
        {
            startHil();
        }
        else
        {
            stopHil();
        }
    }
    
    /**
    * If enabled, connect the JSBSim link.
    */
    void UAS::enableHilJSBSim(bool enable, QString options)
    {
        QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
        if (!link || !simulation) {
            // Delete wrong sim
            if (simulation) {
                stopHil();
                delete simulation;
            }
            simulation = new QGCJSBSimLink(this, options);
        }
        // Connect Flight Gear Link