Skip to content
Snippets Groups Projects
UAS.cc 123 KiB
Newer Older
  • Learn to ignore specific revisions
  • Don Gagne's avatar
    Don Gagne committed
    #endif
    
        }
        else
        {
            // Attempt to set HIL mode
            setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
            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 (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
    
    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();
    
    Lorenz Meier's avatar
    Lorenz Meier committed
            sendMessage(msg);
        }
        else
        {
            // Attempt to set HIL mode
    
            setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
    
    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;
    
        setMode(base_mode | MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
    
        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();
            setMode(base_mode & ~MAV_MODE_FLAG_HIL_ENABLED, custom_mode);
            qDebug() << __FILE__ << __LINE__ << "HIL is onboard not enabled, trying to disable.";
        }
    
        sensorHil = false;
    
    dogmaphobic's avatar
    dogmaphobic committed
    #endif
    
    Don Gagne's avatar
    Don Gagne committed
        QMessageBox::StandardButton button = QGCMessageBox::question(tr("Shutting down the UAS"),
                                                                     tr("Do you want to shut down the onboard computer?"),
                                                                     QMessageBox::Yes | QMessageBox::Cancel,
                                                                     QMessageBox::Cancel);
        if (button == 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(uint8_t base_mode, uint32_t custom_mode) const
    
        QString mode = AutoPilotPluginManager::instance()->getShortModeText(base_mode, custom_mode, autopilot);
    
    
        if (mode.length() == 0)
    
            qDebug() << __FILE__ << __LINE__ << " Unknown mode: base_mode=" << base_mode << " custom_mode=" << custom_mode << " autopilot=" << autopilot;
    
        if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
    
        {
            mode.prepend("A");
        }
        else
        {
            mode.prepend("D");
        }
    
        // HARDWARE IN THE LOOP DECODING
    
        if (base_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL)
    
        //qDebug() << "base_mode=" << base_mode << " custom_mode=" << custom_mode << " autopilot=" << autopilot << ": " << 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 (!_containsLink(link))
    
            _links.append(LinkManager::instance()->sharedPointerForLink(link));
    
            qCDebug(UASLog) << "addLink:" << QString("%1").arg((ulong)link, 0, 16);
    
            connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &UAS::_linkDisconnected);
    
    void UAS::_linkDisconnected(LinkInterface* link)
    
        qCDebug(UASLog) << "_linkDisconnected:" << link->getName();
    
        qCDebug(UASLog) << "link count:" << _links.count();
    
        for (int i=0; i<_links.count(); i++) {
            if (_links[i].data() == link) {
                _links.removeAt(i);
                break;
            }
        }
    
        
        if (_links.count() == 0) {
            // Remove the UAS when all links to it close
            UASManager::instance()->removeUAS(this);
        }
    
    QList<LinkInterface*> UAS::getLinks()
    
        QList<LinkInterface*> list;
        
        foreach (SharedLinkInterface sharedLink, _links) {
            list << sharedLink.data();
        }
        
        return list;
    
    }
    
    /**
    * @rerturn the map of the components
    */
    QMap<int, QString> UAS::getComponents()
    {
        return components;
    }
    
    /**
    * Set the battery specificaitons: empty voltage, warning voltage, and full voltage.
    * @param specifications of the battery
    */
    void UAS::setBatterySpecs(const QString& specs)
    {
    
        batteryRemainingEstimateEnabled = false;
        bool ok;
        QString percent = specs;
        percent = percent.remove("%");
        float temp = percent.toFloat(&ok);
        if (ok)
    
            warnLevelPercent = temp;
    
            emit textMessageReceived(0, 0, MAV_SEVERITY_WARNING, "Could not set battery options, format is wrong");
    
        }
    }
    
    /**
    * @return the battery specifications(empty voltage, warning voltage, full voltage)
    */
    QString UAS::getBatterySpecs()
    {
    
        return QString("%1%").arg(warnLevelPercent);
    
    }
    
    /**
    * @return the time remaining.
    */
    int UAS::calculateTimeRemaining()
    {
    
        // XXX needs fixing
        return 0;
    
    }
    
    /**
     * @return charge level in percent - 0 - 100
     */
    float UAS::getChargeLevel()
    {
        return chargeLevel;
    }
    
    void UAS::startLowBattAlarm()
    {
        if (!lowBattAlarm)
        {
    
            GAudioOutput::instance()->alert(tr("System %1 has low battery").arg(getUASID()));
    
            lowBattAlarm = true;
        }
    }
    
    void UAS::stopLowBattAlarm()
    {
        if (lowBattAlarm)
        {
            lowBattAlarm = false;
        }
    }
    
    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);
    
        sendMessage(message);
        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,
    
                                          0.0f);
            sendMessage(message);
        }
    }
    
    
    bool UAS::_containsLink(LinkInterface* link)
    {
        foreach (SharedLinkInterface sharedLink, _links) {
            if (sharedLink.data() == link) {
                return true;
            }
        }
    
        return false;
    }