Skip to content
Snippets Groups Projects
UAS.cc 129 KiB
Newer Older
  • Learn to ignore specific revisions
  •             stopHil();
                delete simulation;
            }
            simulation = new QGCJSBSimLink(this, options);
        }
        // Connect Flight Gear Link
        link = dynamic_cast<QGCJSBSimLink*>(simulation);
        link->setStartupArguments(options);
    
        if (enable)
        {
            startHil();
        }
        else
        {
            stopHil();
        }
    }
    
    /**
    * If enabled, connect the X-plane gear link.
    */
    void UAS::enableHilXPlane(bool enable)
    {
        QGCXPlaneLink* link = dynamic_cast<QGCXPlaneLink*>(simulation);
        if (!link || !simulation) {
            if (simulation) {
                stopHil();
                delete simulation;
            }
            qDebug() << "CREATED NEW XPLANE LINK";
            simulation = new QGCXPlaneLink(this);
        }
        // Connect X-Plane Link
        if (enable)
        {
            startHil();
        }
        else
        {
            stopHil();
        }
    }
    
    
    /**
    * @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)
    */
    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)
    {
            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);
    
            // 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());
    }
    
    
    /**
    * @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)
    */
    
    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 (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
        {
    
            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);
            sendMessage(msg);
    
        }
        else
        {
            // Attempt to set HIL mode
            mavlink_message_t msg;
            mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
            sendMessage(msg);
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    
    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 (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
        {
            mavlink_message_t msg;
    
            mavlink_msg_hil_sensor_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
    
    Lorenz Meier's avatar
    Lorenz Meier committed
                                       time_us, xacc, yacc, zacc, rollspeed, pitchspeed, yawspeed,
                                         xmag, ymag, zmag, abs_pressure, diff_pressure, pressure_alt, temperature,
                                         fields_changed);
            sendMessage(msg);
    
            lastSendTimeSensors = QGC::groundTimeMilliseconds();
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        }
        else
        {
            // Attempt to set HIL mode
            mavlink_message_t msg;
            mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
            sendMessage(msg);
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    
    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;
    
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        if (this->mode & MAV_MODE_FLAG_HIL_ENABLED)
        {
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            float course = cog;
            // map to 0..2pi
            if (course < 0)
                course += 2.0f * M_PI;
            // 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();
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            sendMessage(msg);
        }
        else
        {
            // Attempt to set HIL mode
            mavlink_message_t msg;
            mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
            sendMessage(msg);
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to enable.";
        }
    }
    
    
    
    /**
    * Connect flight gear link.
    **/
    void UAS::startHil()
    {
        if (hilEnabled) return;
        hilEnabled = true;
    
        sensorHil = false;
    
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
        sendMessage(msg);
    
        // Connect HIL simulation link
        simulation->connectSimulation();
    
    }
    
    /**
    * disable flight gear link.
    */
    void UAS::stopHil()
    {
        if (simulation) simulation->disconnectSimulation();
        mavlink_message_t msg;
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
        sendMessage(msg);
        hilEnabled = false;
    
        sensorHil = false;
    
    }
    
    void UAS::shutdown()
    {
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Shutting down the UAS");
        msgBox.setInformativeText("Do you want to shut down the onboard computer?");
    
        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)
        {
            // If the active UAS is set, execute command
            mavlink_message_t msg;
            mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
            sendMessage(msg);
        }
    }
    
    /**
    * @param x position
    * @param y position
    * @param z position
    * @param yaw
    */
    void UAS::setTargetPosition(float x, float y, float z, float yaw)
    {
        mavlink_message_t msg;
        mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_PATHPLANNING, 1, 1, 1, 0, yaw, x, y, z);
        sendMessage(msg);
    }
    
    /**
     * @return The name of this system as string in human-readable form
     */
    QString UAS::getUASName(void) const
    {
        QString result;
        if (name == "")
        {
            result = tr("MAV ") + result.sprintf("%03d", getUASID());
        }
        else
        {
            result = name;
        }
        return result;
    }
    
    /**
    * @return the state of the uas as a short text.
    */
    const QString& UAS::getShortState() const
    {
        return shortStateText;
    }
    
    
    /**
    * The mode can be autonomous, guided, manual or armed. It will also return if
    
    * hardware in the loop is being used.
    * @return the audio mode text for the id given.
    */
    QString UAS::getAudioModeTextFor(int id)
    {
        QString mode;
        uint8_t modeid = id;
    
        // BASE MODE DECODING
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
        {
            mode += "autonomous";
        }
        else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
        {
            mode += "guided";
        }
    
    Lorenz Meier's avatar
    Lorenz Meier committed
        else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
        {
            mode += "stabilized";
        }
    
        else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
        {
            mode += "manual";
        }
        else
        {
            // Nothing else applies, we're in preflight
            mode += "preflight";
        }
    
        if (modeid != 0)
        {
            mode += " mode";
        }
    
        // ARMED STATE DECODING
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
        {
            mode.append(" and armed");
        }
    
        // HARDWARE IN THE LOOP DECODING
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
        {
            mode.append(" using hardware in the loop simulation");
        }
    
        return mode;
    }
    
    
    /**
    * The mode returned can be auto, stabilized, test, manual, preflight or unknown.
    * @return the short text of the mode for the id given.
    */
    
    * The mode returned can be auto, stabilized, test, manual, preflight or unknown.
    
    * @return the short text of the mode for the id given.
    */
    QString UAS::getShortModeTextFor(int id)
    {
    
        QString mode = "";
    
        uint8_t modeid = id;
    
    
        // BASE MODE DECODING
    
    
        if (modeid == 0)
    
        else {
            if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO){
                mode += "|AUTO";
            }
    
            if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL){
                mode += "|MANUAL";
            }
    
            if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED){
                mode += "|VECTOR";
            }
    
            if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE){
                mode += "|STABILIZED";
            }
    
    
            if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST){
                mode += "|TEST";
            }
    
    
        }
    
        if (mode.length() == 0)
    
            qDebug() << __FILE__ << __LINE__ << " Unknown modeid: " << modeid;
    
        }
    
        // ARMED STATE DECODING
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
        {
            mode.prepend("A");
        }
        else
        {
            mode.prepend("D");
        }
    
        // HARDWARE IN THE LOOP DECODING
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
        {
            mode.prepend("HIL:");
        }
    
    
        qDebug() << "MODE: " << modeid << " " << mode;
    
    
        return mode;
    }
    
    const QString& UAS::getShortMode() const
    {
        return shortModeText;
    }
    
    /**
    * Add the link and connect a signal to it which will be set off when it is destroyed.
    */
    void UAS::addLink(LinkInterface* link)
    {
        if (!links->contains(link))
        {
            links->append(link);
            connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
        }
    }
    
    void UAS::removeLink(QObject* object)
    {
        LinkInterface* link = dynamic_cast<LinkInterface*>(object);
        if (link)
        {
            links->removeAt(links->indexOf(link));
        }
    }
    
    /**
    * @return the list of links
    */
    QList<LinkInterface*>* UAS::getLinks()
    {
        return links;
    }
    
    /**
    * @rerturn the map of the components
    */
    QMap<int, QString> UAS::getComponents()
    {
        return components;
    }
    
    /**
    * Set the battery type and the  number of cells.
    * @param type of the battery
    * @param cells Number of cells.
    */
    void UAS::setBattery(BatteryType type, int cells)
    {
        this->batteryType = type;
        this->cells = cells;
        switch (batteryType)
        {
        case NICD:
            break;
        case NIMH:
            break;
        case LIION:
            break;
        case LIPOLY:
    
            fullVoltage = this->cells * lipoFull;
            emptyVoltage = this->cells * lipoEmpty;
    
            break;
        case LIFE:
            break;
        case AGZN:
            break;
        }
    }
    
    /**
    * Set the battery specificaitons: empty voltage, warning voltage, and full voltage.
    * @param specifications of the battery
    */
    void UAS::setBatterySpecs(const QString& specs)
    {
        if (specs.length() == 0 || specs.contains("%"))
        {
            batteryRemainingEstimateEnabled = false;
            bool ok;
            QString percent = specs;
            percent = percent.remove("%");
            float temp = percent.toFloat(&ok);
            if (ok)
            {
                warnLevelPercent = temp;
            }
            else
            {
                emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
            }
        }
        else
        {
            batteryRemainingEstimateEnabled = true;
            QString stringList = specs;
            stringList = stringList.remove("V");
            stringList = stringList.remove("v");
            QStringList parts = stringList.split(",");
            if (parts.length() == 3)
            {
                float temp;
                bool ok;
                // Get the empty voltage
                temp = parts.at(0).toFloat(&ok);
                if (ok) emptyVoltage = temp;
                // Get the warning voltage
                temp = parts.at(1).toFloat(&ok);
                if (ok) warnVoltage = temp;
                // Get the full voltage
                temp = parts.at(2).toFloat(&ok);
                if (ok) fullVoltage = temp;
            }
            else
            {
                emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
            }
        }
    }
    
    /**
    * @return the battery specifications(empty voltage, warning voltage, full voltage)
    */
    QString UAS::getBatterySpecs()
    {
        if (batteryRemainingEstimateEnabled)
        {
            return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
        }
        else
        {
            return QString("%1%").arg(warnLevelPercent);
        }
    }
    
    /**
    * @return the time remaining.
    */
    int UAS::calculateTimeRemaining()
    {
        quint64 dt = QGC::groundTimeMilliseconds() - startTime;
        double seconds = dt / 1000.0f;
        double voltDifference = startVoltage - currentVoltage;
        if (voltDifference <= 0) voltDifference = 0.00000000001f;
        double dischargePerSecond = voltDifference / seconds;
        int remaining = static_cast<int>((currentVoltage - emptyVoltage) / dischargePerSecond);
        // Can never be below 0
        if (remaining < 0) remaining = 0;
        return remaining;
    }
    
    /**
     * @return charge level in percent - 0 - 100
     */
    float UAS::getChargeLevel()
    {
        if (batteryRemainingEstimateEnabled)
        {
            if (lpVoltage < emptyVoltage)
            {
                chargeLevel = 0.0f;
            }
            else if (lpVoltage > fullVoltage)
            {
                chargeLevel = 100.0f;
            }
            else
            {
                chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
            }
        }
        return chargeLevel;
    }
    
    void UAS::startLowBattAlarm()
    {
        if (!lowBattAlarm)
        {
            GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
            QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency()));
            lowBattAlarm = true;
        }
    }
    
    void UAS::stopLowBattAlarm()
    {
        if (lowBattAlarm)
        {
            GAudioOutput::instance()->stopEmergency();
            lowBattAlarm = false;
        }
    }