Skip to content
Snippets Groups Projects
UAS.cc 70.7 KiB
Newer Older
  • Learn to ignore specific revisions
  •     // 1000 microseconds
    #ifndef _MSC_VER
        else if (time < 1261440000000000LLU)
    #else
        else if (time < 1261440000000000)
    #endif
        {
            //        qDebug() << "GEN time:" << time/1000 + onboardTimeOffset;
            if (onboardTimeOffset == 0 || time < (lastNonNullTime - 100))
            {
                lastNonNullTime = time;
                onboardTimeOffset = QGC::groundTimeMilliseconds() - time/1000;
            }
            if (time > lastNonNullTime) lastNonNullTime = time;
    
            ret = time/1000 + onboardTimeOffset;
        }
        else
        {
            // Time is not zero and larger than 40 years -> has to be
            // a Unix epoch timestamp. Do nothing.
            ret = time/1000;
        }
    
        return ret;
    }
    
    
    * 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()
    {
    
    //    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);
    
    
    Don Gagne's avatar
    Don Gagne committed
            QByteArray tmpImage(header.toStdString().c_str(), header.length());
    
            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!";
    
                return QImage();
    
        // Restart statemachine
        imagePacketsArrived = 0;
    
        imagePackets = 0;
        imageRecBuffer.clear();
    
        return image;
    }
    
    void UAS::requestImage()
    {
    
       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, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);
    
            _vehicle->sendMessage(msg);
    
        }
    }
    
    
    /* MANAGEMENT */
    
    /**
     *
     * @return The uptime in milliseconds
     *
     */
    quint64 UAS::getUptime() const
    {
        if(startTime == 0)
        {
            return 0;
        }
        else
        {
            return QGC::groundTimeMilliseconds() - startTime;
        }
    }
    
    
    //TODO update this to use the parameter manager / param data model instead
    
    void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, const mavlink_param_value_t& rawValue,  mavlink_param_union_t& paramUnion)
    
        QVariant paramValue;
    
        switch (rawValue.param_type) {
            case MAV_PARAM_TYPE_REAL32:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_float);
    
            case MAV_PARAM_TYPE_UINT8:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_uint8);
    
            case MAV_PARAM_TYPE_INT8:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_int8);
    
            case MAV_PARAM_TYPE_UINT16:
                paramValue = QVariant(paramUnion.param_uint16);
                break;
    
    
            case MAV_PARAM_TYPE_INT16:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_int16);
    
            case MAV_PARAM_TYPE_UINT32:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_uint32);
    
            case MAV_PARAM_TYPE_INT32:
    
    Don Gagne's avatar
    Don Gagne committed
                paramValue = QVariant(paramUnion.param_int32);
    
            //-- Note: These are not handled above:
            //
            //   MAV_PARAM_TYPE_UINT64
            //   MAV_PARAM_TYPE_INT64
            //   MAV_PARAM_TYPE_REAL64
            //
            //   No space in message (the only storage allocation is a "float") and not present in mavlink_param_union_t
    
    
            default:
                qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type;
    
        qCDebug(UASLog) << "Received PARAM_VALUE" << paramName << paramValue << rawValue.param_type;
    
        emit parameterUpdate(uasId, compId, paramName, rawValue.param_count, rawValue.param_index, rawValue.param_type, paramValue);
    
    }
    
    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);
    
        _vehicle->sendMessage(msg);
    
    * This can only be done if the system has manual inputs enabled and is armed.
    */
    
    void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode)
    
        static float manualRollAngle = 0.0;
        static float manualPitchAngle = 0.0;
        static float manualYawAngle = 0.0;
        static float manualThrust = 0.0;
        static quint16 manualButtons = 0;
        static quint8 countSinceLastTransmission = 0; // Track how many calls to this function have occurred since the last MAVLink transmission
    
        // Transmit the external setpoints only if they've changed OR if it's been a little bit since they were last transmit. To make sure there aren't issues with
        // response rate, we make sure that a message is transmit when the commands have changed, then one more time, and then switch to the lower transmission rate
        // if no command inputs have changed.
    
        // The default transmission rate is 25Hz, but when no inputs have changed it drops down to 5Hz.
        bool sendCommand = false;
        if (countSinceLastTransmission++ >= 5) {
            sendCommand = true;
            countSinceLastTransmission = 0;
    
        } else if ((!qIsNaN(roll) && roll != manualRollAngle) || (!qIsNaN(pitch) && pitch != manualPitchAngle) ||
                 (!qIsNaN(yaw) && yaw != manualYawAngle) || (!qIsNaN(thrust) && thrust != manualThrust) ||
    
                 buttons != manualButtons) {
            sendCommand = true;
    
            // Ensure that another message will be sent the next time this function is called
            countSinceLastTransmission = 10;
        }
    
        // Now if we should trigger an update, let's do that
        if (sendCommand) {
            // Save the new manual control inputs
            manualRollAngle = roll;
            manualPitchAngle = pitch;
            manualYawAngle = yaw;
            manualThrust = thrust;
            manualButtons = buttons;
    
            mavlink_message_t message;
    
    
            if (joystickMode == Vehicle::JoystickModeAttitude) {
    
                // send an external attitude setpoint command (rate control disabled)
                float attitudeQuaternion[4];
                mavlink_euler_to_quaternion(roll, pitch, yaw, attitudeQuaternion);
                uint8_t typeMask = 0x7; // disable rate control
                mavlink_msg_set_attitude_target_pack(mavlink->getSystemId(),
                    mavlink->getComponentId(),
                    &message,
                    QGC::groundTimeUsecs(),
                    this->uasId,
                    0,
                    typeMask,
                    attitudeQuaternion,
                    0,
                    0,
                    0,
                    thrust
                    );
    
            } else if (joystickMode == Vehicle::JoystickModePosition) {
    
                // Send the the local position setpoint (local pos sp external message)
                static float px = 0;
                static float py = 0;
                static float pz = 0;
                //XXX: find decent scaling
                px -= pitch;
                py += roll;
                pz -= 2.0f*(thrust-0.5);
                uint16_t typeMask = (1<<11)|(7<<6)|(7<<3); // select only POSITION control
                mavlink_msg_set_position_target_local_ned_pack(mavlink->getSystemId(),
                        mavlink->getComponentId(),
                        &message,
                        QGC::groundTimeUsecs(),
                        this->uasId,
                        0,
                        MAV_FRAME_LOCAL_NED,
                        typeMask,
                        px,
                        py,
                        pz,
                        0,
                        0,
                        0,
                        0,
                        0,
                        0,
                        yaw,
                        0
                        );
    
            } else if (joystickMode == Vehicle::JoystickModeForce) {
    
                // Send the the force setpoint (local pos sp external message)
                float dcm[3][3];
                mavlink_euler_to_dcm(roll, pitch, yaw, dcm);
                const float fx = -dcm[0][2] * thrust;
                const float fy = -dcm[1][2] * thrust;
                const float fz = -dcm[2][2] * thrust;
                uint16_t typeMask = (3<<10)|(7<<3)|(7<<0)|(1<<9); // select only FORCE control (disable everything else)
                mavlink_msg_set_position_target_local_ned_pack(mavlink->getSystemId(),
                        mavlink->getComponentId(),
                        &message,
                        QGC::groundTimeUsecs(),
                        this->uasId,
                        0,
                        MAV_FRAME_LOCAL_NED,
                        typeMask,
                        0,
                        0,
                        0,
                        0,
                        0,
                        0,
                        fx,
                        fy,
                        fz,
                        0,
                        0
                        );
    
            } else if (joystickMode == Vehicle::JoystickModeVelocity) {
    
                // Send the the local velocity setpoint (local pos sp external message)
                static float vx = 0;
                static float vy = 0;
                static float vz = 0;
                static float yawrate = 0;
                //XXX: find decent scaling
                vx -= pitch;
                vy += roll;
                vz -= 2.0f*(thrust-0.5);
                yawrate += yaw; //XXX: not sure what scale to apply here
                uint16_t typeMask = (1<<10)|(7<<6)|(7<<0); // select only VELOCITY control
                mavlink_msg_set_position_target_local_ned_pack(mavlink->getSystemId(),
                        mavlink->getComponentId(),
                        &message,
                        QGC::groundTimeUsecs(),
                        this->uasId,
                        0,
                        MAV_FRAME_LOCAL_NED,
                        typeMask,
                        0,
                        0,
                        0,
                        vx,
                        vy,
                        vz,
                        0,
                        0,
                        0,
                        0,
                        yawrate
                        );
    
            } else if (joystickMode == Vehicle::JoystickModeRC) {
    
                // Save the new manual control inputs
                manualRollAngle = roll;
                manualPitchAngle = pitch;
                manualYawAngle = yaw;
                manualThrust = thrust;
                manualButtons = buttons;
    
                // Store scaling values for all 3 axes
                const float axesScaling = 1.0 * 1000.0;
    
                // Calculate the new commands for roll, pitch, yaw, and thrust
                const float newRollCommand = roll * axesScaling;
                // negate pitch value because pitch is negative for pitching forward but mavlink message argument is positive for forward
                const float newPitchCommand = -pitch * axesScaling;
                const float newYawCommand = yaw * axesScaling;
                const float newThrustCommand = thrust * axesScaling;
    
    
                //qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
    
                // Send the MANUAL_COMMAND message
                mavlink_msg_manual_control_pack(mavlink->getSystemId(), mavlink->getComponentId(), &message, this->uasId, newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
    
            _vehicle->sendMessage(message);
    
            // Emit an update in control values to other UI elements, like the HSI display
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw)
    {
    
        const uint8_t base_mode = _vehicle->baseMode();
    
       // If system has manual inputs enabled and is armed
    
        if(((base_mode & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) && (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)) || (base_mode & MAV_MODE_FLAG_HIL_ENABLED))
    
            float q[4];
            mavlink_euler_to_quaternion(roll, pitch, yaw, q);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            float yawrate = 0.0f;
    
    
            quint8 mask = (1 << 0) | (1 << 1) | (1 << 2); // ignore rates
    
            mask |= (1 << 6); // ignore throttle
            mavlink_msg_set_attitude_target_pack(mavlink->getSystemId(), mavlink->getComponentId(),
                                                 &message, QGC::groundTimeMilliseconds(), this->uasId, 0,
                                                 mask, q, 0, 0, 0, 0);
    
            _vehicle->sendMessage(message);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            quint16 position_mask = (1 << 3) | (1 << 4) | (1 << 5) |
    
                (1 << 6) | (1 << 7) | (1 << 8);
    
            mavlink_msg_set_position_target_local_ned_pack(mavlink->getSystemId(), mavlink->getComponentId(),
                                                           &message, QGC::groundTimeMilliseconds(), this->uasId, 0,
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                                                           MAV_FRAME_LOCAL_NED, position_mask, x, y, z, 0, 0, 0, 0, 0, 0, yaw, yawrate);
    
            _vehicle->sendMessage(message);
    
            qDebug() << __FILE__ << __LINE__ << ": SENT 6DOF CONTROL MESSAGES: 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";
        }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    Jean Cyr's avatar
    Jean Cyr committed
    * Order the robot to start receiver pairing
    
    */
    void UAS::pairRX(int rxType, int rxSubType)
    {
    
        mavlink_message_t msg;
    
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_START_RX_PAIR, 0, rxType, rxSubType, 0, 0, 0, 0, 0);
    
        _vehicle->sendMessage(msg);
    
    /**
    * If enabled, connect the flight gear link.
    */
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
    
        Q_UNUSED(configuration);
    
        QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
    
        if (!link) {
    
            // Delete wrong sim
            if (simulation) {
                stopHil();
                delete simulation;
            }
    
            simulation = new QGCFlightGearLink(_vehicle, options);
    
        float noise_scaler = 0.0001f;
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        xacc_var = noise_scaler * 0.2914f;
        yacc_var = noise_scaler * 0.2914f;
        zacc_var = noise_scaler * 0.9577f;
    
        rollspeed_var = noise_scaler * 0.8126f;
        pitchspeed_var = noise_scaler * 0.6145f;
        yawspeed_var = noise_scaler * 0.5852f;
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        xmag_var = noise_scaler * 0.0786f;
        ymag_var = noise_scaler * 0.0566f;
        zmag_var = noise_scaler * 0.0333f;
    
        abs_pressure_var = noise_scaler * 0.5604f;
        diff_pressure_var = noise_scaler * 0.2604f;
        pressure_alt_var = noise_scaler * 0.5604f;
        temperature_var = noise_scaler * 0.7290f;
    
        // Connect Flight Gear Link
        link = dynamic_cast<QGCFlightGearLink*>(simulation);
        link->setStartupArguments(options);
    
    Thomas Gubler's avatar
    Thomas Gubler committed
        link->sensorHilEnabled(sensorHil);
    
        // FIXME: this signal is not on the base hil configuration widget, only on the FG widget
        //QObject::connect(configuration, SIGNAL(barometerOffsetChanged(float)), link, SLOT(setBarometerOffset(float)));
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::enableHilJSBSim(bool enable, QString options)
    {
        QGCJSBSimLink* link = dynamic_cast<QGCJSBSimLink*>(simulation);
    
        if (!link) {
    
            // Delete wrong sim
            if (simulation) {
                stopHil();
                delete simulation;
            }
    
            simulation = new QGCJSBSimLink(_vehicle, options);
    
        }
        // Connect Flight Gear Link
        link = dynamic_cast<QGCJSBSimLink*>(simulation);
        link->setStartupArguments(options);
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    
    /**
    * If enabled, connect the X-plane gear link.
    */
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::enableHilXPlane(bool enable)
    {
        QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
    
        if (!link) {
    
            if (simulation) {
                stopHil();
                delete simulation;
            }
    
            simulation = new QGCXPlaneLink(_vehicle);
    
            float noise_scaler = 0.0001f;
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            xacc_var = noise_scaler * 0.2914f;
            yacc_var = noise_scaler * 0.2914f;
            zacc_var = noise_scaler * 0.9577f;
    
            rollspeed_var = noise_scaler * 0.8126f;
            pitchspeed_var = noise_scaler * 0.6145f;
            yawspeed_var = noise_scaler * 0.5852f;
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            xmag_var = noise_scaler * 0.0786f;
            ymag_var = noise_scaler * 0.0566f;
            zmag_var = noise_scaler * 0.0333f;
    
            abs_pressure_var = noise_scaler * 0.5604f;
            diff_pressure_var = noise_scaler * 0.2604f;
            pressure_alt_var = noise_scaler * 0.5604f;
            temperature_var = noise_scaler * 0.7290f;
    
        }
        // Connect X-Plane Link
        if (enable)
        {
            startHil();
        }
        else
        {
            stopHil();
        }
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    /**
    * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
    * @param roll Roll angle (rad)
    * @param pitch Pitch angle (rad)
    * @param yaw Yaw angle (rad)
    * @param rollspeed Roll angular speed (rad/s)
    * @param pitchspeed Pitch angular speed (rad/s)
    * @param yawspeed Yaw angular speed (rad/s)
    * @param lat Latitude, expressed as * 1E7
    * @param lon Longitude, expressed as * 1E7
    * @param alt Altitude in meters, expressed as * 1000 (millimeters)
    * @param vx Ground X Speed (Latitude), expressed as m/s * 100
    * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
    * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
    * @param xacc X acceleration (mg)
    * @param yacc Y acceleration (mg)
    * @param zacc Z acceleration (mg)
    */
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
                           float pitchspeed, float yawspeed, double lat, double lon, double alt,
                           float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
    {
    
        Q_UNUSED(time_us);
        Q_UNUSED(xacc);
        Q_UNUSED(yacc);
        Q_UNUSED(zacc);
    
            // Emit attitude for cross-check
            emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime());
            emit valueChanged(uasId, "pitch sim", "rad", pitch, getUnixTime());
            emit valueChanged(uasId, "yaw sim", "rad", yaw, getUnixTime());
    
            emit valueChanged(uasId, "roll rate sim", "rad/s", rollspeed, getUnixTime());
            emit valueChanged(uasId, "pitch rate sim", "rad/s", pitchspeed, getUnixTime());
            emit valueChanged(uasId, "yaw rate sim", "rad/s", yawspeed, getUnixTime());
    
            emit valueChanged(uasId, "lat sim", "deg", lat*1e7, getUnixTime());
            emit valueChanged(uasId, "lon sim", "deg", lon*1e7, getUnixTime());
            emit valueChanged(uasId, "alt sim", "deg", alt*1e3, getUnixTime());
    
            emit valueChanged(uasId, "vx sim", "m/s", vx*1e2, getUnixTime());
            emit valueChanged(uasId, "vy sim", "m/s", vy*1e2, getUnixTime());
            emit valueChanged(uasId, "vz sim", "m/s", vz*1e2, getUnixTime());
    
            emit valueChanged(uasId, "IAS sim", "m/s", ind_airspeed, getUnixTime());
            emit valueChanged(uasId, "TAS sim", "m/s", true_airspeed, getUnixTime());
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    /**
    * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
    * @param roll Roll angle (rad)
    * @param pitch Pitch angle (rad)
    * @param yaw Yaw angle (rad)
    * @param rollspeed Roll angular speed (rad/s)
    * @param pitchspeed Pitch angular speed (rad/s)
    * @param yawspeed Yaw angular speed (rad/s)
    * @param lat Latitude, expressed as * 1E7
    * @param lon Longitude, expressed as * 1E7
    * @param alt Altitude in meters, expressed as * 1000 (millimeters)
    * @param vx Ground X Speed (Latitude), expressed as m/s * 100
    * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
    * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
    * @param xacc X acceleration (mg)
    * @param yacc Y acceleration (mg)
    * @param zacc Z acceleration (mg)
    */
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                           float pitchspeed, float yawspeed, double lat, double lon, double alt,
    
                           float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc)
    
        if (_vehicle->hilMode())
    
            float q[4];
    
            double cosPhi_2 = cos(double(roll) / 2.0);
            double sinPhi_2 = sin(double(roll) / 2.0);
            double cosTheta_2 = cos(double(pitch) / 2.0);
            double sinTheta_2 = sin(double(pitch) / 2.0);
            double cosPsi_2 = cos(double(yaw) / 2.0);
            double sinPsi_2 = sin(double(yaw) / 2.0);
            q[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
                    sinPhi_2 * sinTheta_2 * sinPsi_2);
            q[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
                    cosPhi_2 * sinTheta_2 * sinPsi_2);
            q[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
                    sinPhi_2 * cosTheta_2 * sinPsi_2);
            q[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
                    sinPhi_2 * sinTheta_2 * cosPsi_2);
    
            mavlink_message_t msg;
    
            mavlink_msg_hil_state_quaternion_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
    
                                       time_us, q, rollspeed, pitchspeed, yawspeed,
                                       lat*1e7f, lon*1e7f, alt*1000, vx*100, vy*100, vz*100, ind_airspeed*100, true_airspeed*100, xacc*1000/9.81, yacc*1000/9.81, zacc*1000/9.81);
    
            _vehicle->sendMessage(msg);
    
    Don Gagne's avatar
    Don Gagne committed
            _vehicle->setHilMode(true);
    
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    #ifndef __mobile__
    float UAS::addZeroMeanNoise(float truth_meas, float noise_var)
    {
    
    dogmaphobic's avatar
    dogmaphobic committed
        /* Calculate normally distributed variable noise with mean = 0 and variance = noise_var.  Calculated according to
    
        Box-Muller transform */
        static const float epsilon = std::numeric_limits<float>::min(); //used to ensure non-zero uniform numbers
        static float z0; //calculated normal distribution random variables with mu = 0, var = 1;
        float u1, u2;        //random variables generated from c++ rand();
    
        /*Generate random variables in range (0 1] */
        do
        {
            //TODO seed rand() with srand(time) but srand(time should be called once on startup)
            //currently this will generate repeatable random noise
            u1 = rand() * (1.0 / RAND_MAX);
            u2 = rand() * (1.0 / RAND_MAX);
        }
        while ( u1 <= epsilon );  //Have a catch to ensure non-zero for log()
    
    
        z0 = sqrt(-2.0 * log(u1)) * cos(2.0f * M_PI * u2); //calculate normally distributed variable with mu = 0, var = 1
    
        //TODO add bias term that changes randomly to simulate accelerometer and gyro bias the exf should handle these
        //as well
    
        float noise = z0 * sqrt(noise_var); //calculate normally distributed variable with mu = 0, std = var^2
    
        //Finally gaurd against any case where the noise is not real
    
    /*
    * @param abs_pressure Absolute Pressure (hPa)
    * @param diff_pressure Differential Pressure  (hPa)
    */
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    Lorenz Meier's avatar
    Lorenz Meier committed
    void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
    
                                        float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed)
    
    Lorenz Meier's avatar
    Lorenz Meier committed
    {
    
        if (_vehicle->hilMode())
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        {
    
            float xacc_corrupt = addZeroMeanNoise(xacc, xacc_var);
            float yacc_corrupt = addZeroMeanNoise(yacc, yacc_var);
            float zacc_corrupt = addZeroMeanNoise(zacc, zacc_var);
            float rollspeed_corrupt = addZeroMeanNoise(rollspeed,rollspeed_var);
            float pitchspeed_corrupt = addZeroMeanNoise(pitchspeed,pitchspeed_var);
            float yawspeed_corrupt = addZeroMeanNoise(yawspeed,yawspeed_var);
            float xmag_corrupt = addZeroMeanNoise(xmag, xmag_var);
            float ymag_corrupt = addZeroMeanNoise(ymag, ymag_var);
            float zmag_corrupt = addZeroMeanNoise(zmag, zmag_var);
            float abs_pressure_corrupt = addZeroMeanNoise(abs_pressure,abs_pressure_var);
            float diff_pressure_corrupt = addZeroMeanNoise(diff_pressure, diff_pressure_var);
            float pressure_alt_corrupt = addZeroMeanNoise(pressure_alt, pressure_alt_var);
            float temperature_corrupt = addZeroMeanNoise(temperature,temperature_var);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            mavlink_message_t msg;
    
            mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
    
                                       time_us, xacc_corrupt, yacc_corrupt, zacc_corrupt, rollspeed_corrupt, pitchspeed_corrupt,
    
    dogmaphobic's avatar
    dogmaphobic committed
                                        yawspeed_corrupt, xmag_corrupt, ymag_corrupt, zmag_corrupt, abs_pressure_corrupt,
    
                                        diff_pressure_corrupt, pressure_alt_corrupt, temperature_corrupt, fields_changed);
    
            _vehicle->sendMessage(msg);
    
            lastSendTimeSensors = QGC::groundTimeMilliseconds();
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        }
        else
        {
            // Attempt to set HIL mode
    
    Don Gagne's avatar
    Don Gagne committed
            _vehicle->setHilMode(true);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
                        float flow_comp_m_y, quint8 quality, float ground_distance)
    {
    
    Don Gagne's avatar
    Don Gagne committed
        // FIXME: This needs to be updated for new mavlink_msg_hil_optical_flow_pack api
    
    Don Gagne's avatar
    Don Gagne committed
        Q_UNUSED(time_us);
        Q_UNUSED(flow_x);
        Q_UNUSED(flow_y);
        Q_UNUSED(flow_comp_m_x);
        Q_UNUSED(flow_comp_m_y);
        Q_UNUSED(quality);
        Q_UNUSED(ground_distance);
    
        if (_vehicle->hilMode())
    
    Don Gagne's avatar
    Don Gagne committed
    #if 0
    
            mavlink_message_t msg;
            mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
    
    Don Gagne's avatar
    Don Gagne committed
                                       time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
    
            _vehicle->sendMessage(msg);
    
            lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
    
    Don Gagne's avatar
    Don Gagne committed
    #endif
    
        }
        else
        {
            // Attempt to set HIL mode
    
    Don Gagne's avatar
    Don Gagne committed
            _vehicle->setHilMode(true);
    
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
    
    Lorenz Meier's avatar
    Lorenz Meier committed
    {
    
        // Only send at 10 Hz max rate
        if (QGC::groundTimeMilliseconds() - lastSendTimeGPS < 100)
            return;
    
    
        if (_vehicle->hilMode())
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        {
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            float course = cog;
            // map to 0..2pi
            if (course < 0)
    
    Don Gagne's avatar
    Don Gagne committed
                course += 2.0f * static_cast<float>(M_PI);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            // scale from radians to degrees
            course = (course / M_PI) * 180.0f;
    
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            mavlink_message_t msg;
    
            mavlink_msg_hil_gps_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
                                       time_us, fix_type, lat*1e7, lon*1e7, alt*1e3, eph*1e2, epv*1e2, vel*1e2, vn*1e2, ve*1e2, vd*1e2, course*1e2, satellites);
    
            lastSendTimeGPS = QGC::groundTimeMilliseconds();
    
            _vehicle->sendMessage(msg);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        }
        else
        {
            // Attempt to set HIL mode
    
    Don Gagne's avatar
    Don Gagne committed
            _vehicle->setHilMode(true);
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    /**
    * Connect flight gear link.
    **/
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
    void UAS::startHil()
    {
        if (hilEnabled) return;
        hilEnabled = true;
    
        sensorHil = false;
    
    Don Gagne's avatar
    Don Gagne committed
        _vehicle->setHilMode(true);
    
        qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
    
        // Connect HIL simulation link
        simulation->connectSimulation();
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    dogmaphobic's avatar
    dogmaphobic committed
    #ifndef __mobile__
    
       if (simulation && simulation->isConnected()) {
           simulation->disconnectSimulation();
           _vehicle->setHilMode(false);
           qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
       }
    
        sensorHil = false;
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    
    /**
    * @rerturn the map of the components
    */
    QMap<int, QString> UAS::getComponents()
    {
        return components;
    }
    
    
    void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax)
    
        mavlink_message_t message;
    
    
        char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
        // Copy string into buffer, ensuring not to exceed the buffer size
        for (unsigned int i = 0; i < sizeof(param_id_cstr); i++)
        {
            if ((int)i < param_id.length())
            {
                param_id_cstr[i] = param_id.toLatin1()[i];
            }
        }
    
    
        mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                      mavlink->getComponentId(),
                                      &message,
                                      this->uasId,
                                      0,
    
                                      -1,
                                      param_rc_channel_index,
    
                                      value0,
                                      scale,
                                      valueMin,
                                      valueMax);
    
        _vehicle->sendMessage(message);
    
    dogmaphobic's avatar
    dogmaphobic committed
        //qDebug() << "Mavlink message sent";
    
    void UAS::unsetRCToParameterMap()
    {
    
        char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
    
    
        for (int i = 0; i < 3; i++) {
            mavlink_message_t message;
            mavlink_msg_param_map_rc_pack(mavlink->getSystemId(),
                                          mavlink->getComponentId(),
                                          &message,
                                          this->uasId,
                                          0,
    
                                          0.0f,
                                          0.0f,
    
            _vehicle->sendMessage(message);
    
    
    void UAS::_say(const QString& text, int severity)
    {
    
        Q_UNUSED(severity);
        qgcApp()->toolbox()->audioOutput()->say(text);
    
    Don Gagne's avatar
    Don Gagne committed
    
    void UAS::shutdownVehicle(void)
    {
    #ifndef __mobile__
        stopHil();
        if (simulation) {
            // wait for the simulator to exit
            simulation->wait();
            simulation->disconnectSimulation();
            simulation->deleteLater();
        }
    #endif
        _vehicle = NULL;
    }