Skip to content
Snippets Groups Projects
UAS.cc 54.2 KiB
Newer Older
  • Learn to ignore specific revisions
  • pixhawk's avatar
    pixhawk committed
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 7;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::enableExtra2Transmission(bool enabled)
    {
    
    pixhawk's avatar
    pixhawk committed
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 8;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::enableExtra3Transmission(bool enabled)
    {
    
    pixhawk's avatar
    pixhawk committed
        // Buffers to write data to
        mavlink_message_t msg;
        mavlink_request_data_stream_t stream;
        // Select the message to request from now on
        stream.req_stream_id = 9;
        // Select the update rate in Hz the message should be send
        stream.req_message_rate = 200;
    
        // Start / stop the message
        stream.start_stop = (enabled) ? 1 : 0;
        // The system which should take this command
        stream.target_system = uasId;
        // The component / subsystem which should take this command
        stream.target_component = 0;
        // Encode and send the message
        mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
    
    lm's avatar
    lm committed
    /**
     * Set a parameter value onboard
     *
     * @param component The component to set the parameter
     * @param id Name of the parameter
     * @param value Parameter value
     */
    
    void UAS::setParameter(int component, QString id, float value)
    
        mavlink_message_t msg;
        mavlink_param_set_t p;
        p.param_value = value;
    
        p.target_system = (uint8_t)uasId;
        p.target_component = (uint8_t)component;
    
        // Copy string into buffer, ensuring not to exceed the buffer size    
    
        for (unsigned int i = 0; i < sizeof(p.param_id); i++)
    
    lm's avatar
    lm committed
            // String characters
    
            if ((int)i < id.length() && i < (sizeof(p.param_id) - 1))
    
    lm's avatar
    lm committed
            {
    
    lm's avatar
    lm committed
            }
            // Null termination at end of string or end of buffer
    
            else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1))
    
    lm's avatar
    lm committed
            {
                p.param_id[i] = '\0';
            }
            // Zero fill
            else
            {
                p.param_id[i] = 0;
            }
    
        mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p);
    
    pixhawk's avatar
    pixhawk committed
    /**
    
    lm's avatar
    lm committed
     * Launches the system
    
    pixhawk's avatar
    pixhawk committed
     *
     **/
    void UAS::launch()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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, (uint8_t)MAV_ACTION_LAUNCH);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /**
     * Depending on the UAS, this might make the rotors of a helicopter spinning
     *
     **/
    void UAS::enable_motors()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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, (uint8_t)MAV_ACTION_MOTORS_START);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /**
     * @warning Depending on the UAS, this might completely stop all motors.
     *
     **/
    void UAS::disable_motors()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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, (uint8_t)MAV_ACTION_MOTORS_STOP);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
    {
        // Scale values
        double rollPitchScaling = 0.2f;
        double yawScaling = 0.5f;
        double thrustScaling = 1.0f;
    
        manualRollAngle = roll * rollPitchScaling;
        manualPitchAngle = pitch * rollPitchScaling;
        manualYawAngle = yaw * yawScaling;
        manualThrust = thrust * thrustScaling;
    
    
    lm's avatar
    lm committed
    //    if(mode == (int)MAV_MODE_MANUAL)
    //    {
    
    pixhawk's avatar
    pixhawk committed
            mavlink_message_t message;
    
    pixhawk's avatar
    pixhawk committed
            mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
    
    pixhawk's avatar
    pixhawk committed
            sendMessage(message);
            qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
    
            emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
    
    lm's avatar
    lm committed
    //    }
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    pixhawk's avatar
    pixhawk committed
    void UAS::receiveButton(int buttonIndex)
    {
        switch (buttonIndex)
        {
        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!";
    
    }
    
    
    /*void UAS::requestWaypoints()
    
    pixhawk's avatar
    pixhawk committed
    {
    //    mavlink_message_t msg;
    //    mavlink_msg_waypoint_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 25);
    //    // Send message twice to increase chance of reception
    //    sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
        waypointManager.requestWaypoints();
        qDebug() << "UAS Request WPs";
    
    pixhawk's avatar
    pixhawk committed
    void UAS::setWaypoint(Waypoint* wp)
    {
    
    pixhawk's avatar
    pixhawk committed
    //    mavlink_message_t msg;
    //    mavlink_waypoint_set_t set;
    //    set.id = wp->id;
    //    //QString name = wp->name;
    //    // FIXME Check if this works properly
    //    //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
    //    //strcpy((char*)set.name, name.toStdString().c_str());
    //    set.autocontinue = wp->autocontinue;
    //    set.target_component = 25; // FIXME
    //    set.target_system = uasId;
    //    set.active = wp->current;
    //    set.x = wp->x;
    //    set.y = wp->y;
    //    set.z = wp->z;
    //    set.yaw = wp->yaw;
    //    mavlink_msg_waypoint_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &set);
    //    // Send message twice to increase chance of reception
    //    sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::setWaypointActive(int id)
    {
    
    pixhawk's avatar
    pixhawk committed
    //    mavlink_message_t msg;
    //    mavlink_waypoint_set_active_t active;
    //    active.id = id;
    //    active.target_system = uasId;
    //    active.target_component = 25; // FIXME
    //    mavlink_msg_waypoint_set_active_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &active);
    //    // Send message twice to increase chance of reception
    //    sendMessage(msg);
    //    sendMessage(msg);
    //    // TODO This should be not directly emitted, but rather being fed back from the UAS
    //    emit waypointSelected(getUASID(), id);
    }
    
    void UAS::clearWaypointList()
    {
    //    mavlink_message_t msg;
    //    // FIXME
    //    mavlink_waypoint_clear_list_t clist;
    //    clist.target_system = uasId;
    //    clist.target_component = 25;  // FIXME
    //    mavlink_msg_waypoint_clear_list_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &clist);
    //    sendMessage(msg);
    //    qDebug() << "UAS clears Waypoints!";
    
    pixhawk's avatar
    pixhawk committed
    
    
    void UAS::halt()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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_HALT);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    void UAS::go()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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_CONTINUE);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        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;
    
    pixhawk's avatar
    pixhawk committed
        // 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_RETURN);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        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()
    {
    
        mavlink_message_t msg;
    
    pixhawk's avatar
    pixhawk committed
        // 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_LAND);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
    }
    
    /**
     * All systems are immediately shut down (e.g. the main power line is cut).
     * @warning This might lead to a crash
     *
     * The command will not be executed until emergencyKILLConfirm is issues immediately afterwards
     */
    bool UAS::emergencyKILL()
    {
        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;
    
    pixhawk's avatar
    pixhawk committed
            // 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);
    
    pixhawk's avatar
    pixhawk committed
            result = true;
        }
        return result;
    }
    
    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?");
        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;
    
    pixhawk's avatar
    pixhawk committed
            // 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_SHUTDOWN);
    
            // Send message twice to increase chance of reception
            sendMessage(msg);
            sendMessage(msg);
    
    pixhawk's avatar
    pixhawk committed
            result = true;
        }
    }
    
    
    void UAS::setTargetPosition(float x, float y, float z, float yaw)
    {
        mavlink_message_t msg;
        mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);
    
        // Send message twice to increase chance of reception
        sendMessage(msg);
        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;
        if (name == "")
        {
            result = tr("MAV ") + result.sprintf("%03d", getUASID());
        }
        else
        {
            result = name;
        }
        return result;
    }
    
    void UAS::addLink(LinkInterface* link)
    {
        if (!links->contains(link))
        {
            links->append(link);
        }
        //links->append(link);
        //qDebug() << " ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK ADDED LINK";
    }
    
    /**
     * @brief Get the links associated with this robot
     *
     **/
    QList<LinkInterface*>* UAS::getLinks()
    {
        return links;
    }
    
    
    
    void UAS::setBattery(BatteryType type, int cells)
    {
        this->batteryType = type;
        this->cells = cells;
        switch (batteryType)
        {
    
    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;
        }
    }
    
    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
     */
    
    pixhawk's avatar
    pixhawk committed
    double UAS::getChargeLevel()
    {
    
        float chargeLevel;
        if (lpVoltage < emptyVoltage)
        {
            chargeLevel = 0.0f;
        }
        else if (lpVoltage > fullVoltage)
        {
            chargeLevel = 100.0f;
        }
        else
        {
            chargeLevel = 100.0f * ((lpVoltage - emptyVoltage)/(fullVoltage - emptyVoltage));
        }
        return chargeLevel;
    
    pixhawk's avatar
    pixhawk committed
    }
    
    
    lm's avatar
    lm committed
    void UAS::startLowBattAlarm()
    {
        if (!lowBattAlarm)
        {
    
            GAudioOutput::instance()->alert("LOW BATTERY");
            QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
    
    lm's avatar
    lm committed
            lowBattAlarm = true;
        }
    }
    
    void UAS::stopLowBattAlarm()
    {
        if (lowBattAlarm)
        {
            GAudioOutput::instance()->stopEmergency();
            lowBattAlarm = false;
        }
    }