Skip to content
Snippets Groups Projects
UAS.cc 83.1 KiB
Newer Older
  • Learn to ignore specific revisions
  • pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::receiveButton(int buttonIndex)
    {
    
    pixhawk's avatar
    pixhawk committed
        case 0:
    
    pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
            break;
        case 1:
    
    pixhawk's avatar
    pixhawk committed
    
    
    pixhawk's avatar
    pixhawk committed
            break;
        default:
    
            break;
        }
    
        //    qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
    
    pixhawk's avatar
    pixhawk committed
    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);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    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);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /** Order the robot to return home / to land on the runway **/
    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);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /**
     * 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();
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /**
    
    lm's avatar
    lm committed
     * Shut down this mav - All onboard systems are immediately shut down (e.g. the main power line is cut).
    
    pixhawk's avatar
    pixhawk committed
     * @warning This might lead to a crash
     *
     * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
     */
    bool UAS::emergencyKILL()
    {
    
    lm's avatar
    lm committed
        // 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;
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    lm's avatar
    lm committed
    void UAS::enableHil(bool enable)
    {
        // Connect Flight Gear Link
        if (enable)
        {
    
            startHil();
    
    lm's avatar
    lm committed
        }
        else
        {
    
            stopHil();
    
    lm's avatar
    lm committed
        }
    }
    
    /**
    * @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(uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
                        float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
                        int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
    {
        mavlink_message_t msg;
        mavlink_msg_hil_state_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, time_us, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
        sendMessage(msg);
    }
    
    
    
    void UAS::startHil()
    {
    
    lm's avatar
    lm committed
        // Connect Flight Gear Link
        simulation->connectSimulation();
    
        mavlink_message_t msg;
    
    LM's avatar
    LM committed
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode | MAV_MODE_FLAG_HIL_ENABLED, navMode);
    
        sendMessage(msg);
    
    void UAS::stopHil()
    {
    
    lm's avatar
    lm committed
        simulation->disconnectSimulation();
    
        mavlink_message_t msg;
    
    LM's avatar
    LM committed
        mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode);
    
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    void UAS::shutdown()
    {
    
        bool result = false;
        QMessageBox msgBox;
        msgBox.setIcon(QMessageBox::Critical);
        msgBox.setText("Shutting down the UAS");
        msgBox.setInformativeText("Do you want to shut down the onboard computer?");
    
    lm's avatar
    lm committed
    
    
        msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
        msgBox.setDefaultButton(QMessageBox::Cancel);
        int ret = msgBox.exec();
    
    lm's avatar
    lm committed
    
    
        // Close the message box shortly after the click to prevent accidental clicks
        QTimer::singleShot(5000, &msgBox, SLOT(reject()));
    
    lm's avatar
    lm committed
    
    
        if (ret == QMessageBox::Yes)
        {
            // If the active UAS is set, execute command
            mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
            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);
            result = true;
        }
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    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, 2, 3, 0, yaw, x, y, z);
    
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    /**
     * @return The name of this system as string in human-readable form
     */
    
    QString UAS::getUASName(void) const
    
    pixhawk's avatar
    pixhawk committed
    {
        QString result;
    
    pixhawk's avatar
    pixhawk committed
            result = tr("MAV ") + result.sprintf("%03d", getUASID());
    
    pixhawk's avatar
    pixhawk committed
            result = name;
        }
        return result;
    }
    
    
    const QString& UAS::getShortState() const
    {
        return shortStateText;
    }
    
    
    QString UAS::getShortModeTextFor(int id)
    {
        QString mode;
    
    LM's avatar
    LM committed
        uint8_t modeid = id;
    
        qDebug() << "MODE:" << modeid;
    
    LM's avatar
    LM committed
        // BASE MODE DECODING
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
    
    LM's avatar
    LM committed
        {
    
    pixhawk's avatar
    pixhawk committed
            mode += "AUTO";
    
    LM's avatar
    LM committed
        }
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
    
    LM's avatar
    LM committed
        {
    
    pixhawk's avatar
    pixhawk committed
            mode += "GUIDED";
    
    LM's avatar
    LM committed
        }
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
    
    LM's avatar
    LM committed
        {
    
    pixhawk's avatar
    pixhawk committed
            mode += "STABILIZED";
    
    LM's avatar
    LM committed
        }
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
    
    LM's avatar
    LM committed
        {
    
    pixhawk's avatar
    pixhawk committed
            mode += "TEST";
    
    LM's avatar
    LM committed
        }
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
    
    LM's avatar
    LM committed
        {
    
    pixhawk's avatar
    pixhawk committed
            mode += "MANUAL";
    
    LM's avatar
    LM committed
        }
    
    pixhawk's avatar
    pixhawk committed
    
        if (modeid == 0)
    
    LM's avatar
    LM committed
        {
    
            mode = "PREFLIGHT";
    
    LM's avatar
    LM committed
        }
    
        // ARMED STATE DECODING
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
    
    LM's avatar
    LM committed
        {
            mode.prepend("A|");
        }
        else
        {
            mode.prepend("D|");
        }
    
        // HARDWARE IN THE LOOP DECODING
    
    pixhawk's avatar
    pixhawk committed
        if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
    
    LM's avatar
    LM committed
        {
            mode.prepend("HIL:");
    
    const QString& UAS::getShortMode() const
    {
        return shortModeText;
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::addLink(LinkInterface* link)
    {
    
    pixhawk's avatar
    pixhawk committed
            links->append(link);
    
            connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*)));
    
    pixhawk's avatar
    pixhawk committed
        }
    }
    
    
    void UAS::removeLink(QObject* object)
    {
        LinkInterface* link = dynamic_cast<LinkInterface*>(object);
    
            links->removeAt(links->indexOf(link));
        }
    }
    
    
    pixhawk's avatar
    pixhawk committed
    QList<LinkInterface*>* UAS::getLinks()
    {
        return links;
    }
    
    
    LM's avatar
    LM committed
    QMap<int, QString> UAS::getComponents()
    {
        return components;
    }
    
    
    pixhawk's avatar
    pixhawk committed
    
    
    void UAS::setBattery(BatteryType type, int cells)
    {
        this->batteryType = type;
        this->cells = cells;
    
    lm's avatar
    lm committed
        case NICD:
    
    pixhawk's avatar
    pixhawk committed
            break;
    
    lm's avatar
    lm committed
        case NIMH:
    
    pixhawk's avatar
    pixhawk committed
            break;
    
    lm's avatar
    lm committed
        case LIION:
    
    pixhawk's avatar
    pixhawk committed
            break;
    
    lm's avatar
    lm committed
        case LIPOLY:
    
    pixhawk's avatar
    pixhawk committed
            fullVoltage = this->cells * UAS::lipoFull;
            emptyVoltage = this->cells * UAS::lipoEmpty;
            break;
    
    lm's avatar
    lm committed
        case LIFE:
    
    pixhawk's avatar
    pixhawk committed
            break;
    
    lm's avatar
    lm committed
        case AGZN:
    
    pixhawk's avatar
    pixhawk committed
            break;
        }
    }
    
    
    void UAS::setBatterySpecs(const QString& specs)
    {
    
        if (specs.length() == 0 || specs.contains("%"))
        {
    
            batteryRemainingEstimateEnabled = false;
    
            QString percent = specs;
            percent = percent.remove("%");
            float temp = percent.toFloat(&ok);
    
                warnLevelPercent = temp;
    
                emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
            }
    
            batteryRemainingEstimateEnabled = true;
            QString stringList = specs;
            stringList = stringList.remove("V");
            stringList = stringList.remove("v");
            QStringList parts = stringList.split(",");
    
                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;
    
                emit textMessageReceived(0, 0, 0, "Could not set battery options, format is wrong");
            }
    
            return QString("%1V,%2V,%3V").arg(emptyVoltage).arg(warnVoltage).arg(fullVoltage);
    
            return QString("%1%").arg(warnLevelPercent);
        }
    
    pixhawk's avatar
    pixhawk committed
    int UAS::calculateTimeRemaining()
    {
        quint64 dt = MG::TIME::getGroundTimeNow() - 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;
    }
    
    
    lm's avatar
    lm committed
    /**
     * @return charge level in percent - 0 - 100
     */
    
    float UAS::getChargeLevel()
    
    pixhawk's avatar
    pixhawk committed
    {
    
        if (batteryRemainingEstimateEnabled)
        {
            if (lpVoltage < emptyVoltage)
            {
    
                chargeLevel = 0.0f;
    
                chargeLevel = 100.0f;
    
                chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
            }
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    lm's avatar
    lm committed
    void UAS::startLowBattAlarm()
    {
    
            GAudioOutput::instance()->alert(tr("system %1 has low battery").arg(getUASName()));
    
            QTimer::singleShot(2500, GAudioOutput::instance(), SLOT(startEmergency()));
    
    lm's avatar
    lm committed
            lowBattAlarm = true;
        }
    }
    
    void UAS::stopLowBattAlarm()
    {
    
    lm's avatar
    lm committed
            GAudioOutput::instance()->stopEmergency();
            lowBattAlarm = false;
        }
    }