Skip to content
Snippets Groups Projects
UAS.cc 111 KiB
Newer Older
  • Learn to ignore specific revisions
  • }
    
    /**
    * 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 * UAS::lipoFull;
            emptyVoltage = this->cells * UAS::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;
        }
    }