.. _program_listing_file__tmp_ws_src_adaptive_component_include_adaptive_component.hpp: Program Listing for File adaptive_component.hpp =============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/adaptive_component/include/adaptive_component.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* ____ ____ / /\/ / /___/ \ / Copyright (c) 2021, Xilinx®. \ \ \/ Author: Víctor Mayoral Vilches \ \ / / /___/ /\ \ \ / \ \___\/\___\ Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. */ #ifndef ADAPTIVE_COMPONENT_HPP_ #define ADAPTIVE_COMPONENT_HPP_ #include "rclcpp/rclcpp.hpp" #include "rclcpp/executor.hpp" #include "rclcpp/visibility_control.hpp" namespace composition { class AdaptiveComponent : public rclcpp::Node { public: // Define within the class to avoid polluting the global namespace enum Hardware { CPU = 0, FPGA = 1, GPU = 2, }; RCLCPP_PUBLIC AdaptiveComponent(const rclcpp::NodeOptions & options) : Node("adaptive_component", options) {}; RCLCPP_PUBLIC AdaptiveComponent( const rclcpp::NodeOptions & options, std::shared_ptr cpu_node, std::shared_ptr fpga_node, std::shared_ptr gpu_node, const int adaptive_value ) : Node("adaptive_component", options), cpu_node_(cpu_node), fpga_node_(fpga_node), gpu_node_(gpu_node), adaptive_value_(adaptive_value) { initialize(); } RCLCPP_PUBLIC AdaptiveComponent( const std::string &node_name, const rclcpp::NodeOptions & options, std::shared_ptr cpu_node = nullptr, std::shared_ptr fpga_node = nullptr, std::shared_ptr gpu_node = nullptr, const int adaptive_value = 0 ) : Node(node_name, options), cpu_node_(cpu_node), fpga_node_(fpga_node), gpu_node_(gpu_node), adaptive_value_(adaptive_value), compute_resources_{cpu_node_, fpga_node_, gpu_node_} { initialize(); } RCLCPP_PUBLIC void add_cpu(std::shared_ptr node_ptr) {cpu_node_ = node_ptr;}; RCLCPP_PUBLIC void add_fpga(std::shared_ptr node_ptr) {fpga_node_ = node_ptr;}; RCLCPP_PUBLIC void add_gpu(std::shared_ptr node_ptr) {gpu_node_ = node_ptr;}; protected: // and reconfigure computations appropriately. RCLCPP_PUBLIC void on_timer(void); // Actioned in a detached thread RCLCPP_PUBLIC void spin(void); // /// Internal thread to spin executor // std::shared_ptr hilo_; rclcpp::executors::SingleThreadedExecutor exec_; // Should be nullptr by default, C++11 spec. std::shared_ptr cpu_node_; std::shared_ptr fpga_node_; std::shared_ptr gpu_node_; rclcpp::TimerBase::SharedPtr timer_; int adaptive_value_; std::shared_ptr compute_resources_[3]; // TODO: reconsider if a more synthetic implementation is used (see cpp) // std::string compute_resources_names_[3] = {"CPU", "FPGA", "GPU"}; private: RCLCPP_PUBLIC void initialize(void); }; } // namespace composition #endif // ADAPTIVE_COMPONENT_HPP_