Class AdaptiveComponent
Defined in File adaptive_component.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class composition::AdaptiveComponent : public rclcpp::Node
A composable container for Adaptive ROS 2 Node computations.
Select between FPGA, CPU or GPU at run-time.
Nodes using hardware acceleration are able to perform computations faster relying on FPGAs or GPUs, improving performance. Adaptive ROS 2 Nodes leverage hardware acceleration at run-time, allowing to select which computational resource the Node uses on-the-go, providing with a finer-grained control over the resources the computional graphs use in the underlying hardware.
AdaptiveComponent is a ROS 2 Node subclass programmed as a Component and including its own single threaded executor to build adaptive computations. Adaptive ROS 2 Nodes can then be built easily with it. Adaptive behavior is controlled through the “adaptive” ROS 2 parameter.
Public Functions
-
inline RCLCPP_PUBLIC AdaptiveComponent(const rclcpp::NodeOptions &options)
Constructor.
- Parameters
options – [in] Options used to configure the executor.
Constructor.
- Parameters
options – [in] Options used to configure the executor.
cpu_node – [in] std::shared_ptr<rclcpp::Node> Node for CPU computations.
fpga_node – [in] std::shared_ptr<rclcpp::Node> Node for FPGA computations.
fpga_node – [in] std::shared_ptr<rclcpp::Node> Node for GPU computations.
adaptive_value – [in] int initial value for “adaptive” ROS parameter. Defines what’s the initial compute substrate that’s used.
Default constructor.
- Parameters
node_name – [in] std::string Adaptive Node name.
options – [in] Options used to configure the executor.
cpu_node – [in] std::shared_ptr<rclcpp::Node> Node for CPU computations.
fpga_node – [in] std::shared_ptr<rclcpp::Node> Node for FPGA computations.
fpga_node – [in] std::shared_ptr<rclcpp::Node> Node for GPU computations.
adaptive_value – [in] int initial value for “adaptive” ROS parameter and defines what’s the initial compute substrate that’s used.
- inline RCLCPP_PUBLIC void add_cpu (std::shared_ptr< rclcpp::Node > node_ptr)
Add CPU Node manually.
- inline RCLCPP_PUBLIC void add_fpga (std::shared_ptr< rclcpp::Node > node_ptr)
Add FPGA Node manually.
- inline RCLCPP_PUBLIC void add_gpu (std::shared_ptr< rclcpp::Node > node_ptr)
Add GPU Node manually.
Protected Functions
- RCLCPP_PUBLIC void on_timer (void)
Timer callback at 1 second, used to update “adaptive” parameter.
- RCLCPP_PUBLIC void spin (void)
Spin internal single threaded executor.
Protected Attributes
-
rclcpp::executors::SingleThreadedExecutor exec_
Internal AdaptiveComponent container’s executor.
-
std::shared_ptr<rclcpp::Node> cpu_node_
Computational Node for the CPU.
-
std::shared_ptr<rclcpp::Node> fpga_node_
Computational Node for the FPGA.
-
std::shared_ptr<rclcpp::Node> gpu_node_
Computational Node for the GPU.
-
rclcpp::TimerBase::SharedPtr timer_
AdaptiveCoponent internal timer.
-
int adaptive_value_
Mirrors the Node’s “adaptive” ROS 2 parameter.
-
std::shared_ptr<rclcpp::Node> compute_resources_[3]
Pointers to nodes, simplify interactions.
-
inline RCLCPP_PUBLIC AdaptiveComponent(const rclcpp::NodeOptions &options)