Skip to content

ROS 2 package examples demonstrating the use of hardware acceleration.

License

Notifications You must be signed in to change notification settings

ros-acceleration/acceleration_examples

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

acceleration_examples

acceleration_examples is a meta-package that contain various package examples demonstrating the use of hardware acceleration in ROS 2. Each one of these examples aims to support all hardware acceleration technology solutions complying with REP-2008 (see pending PR). By doing so, acceleration_examples aims to a) illustrate ROS package maintainers and ROS users how to build their own acceleration kernels and b) guarantee interoperability across technologies complying with REP-2008. Refer to the community repository for the reference hardware platforms.

In turn, a CI system will be set to build the meta-package against all suported hardware.

Quick access

ROS 2 Node acceleration
publisher_xilinx simple_adder vadd_publisher
doublevadd_publisher offloaded_doublevadd_publisher accelerated_vadd_publisher
faster_doublevadd_publisher multiple_doublevadd_publisher streaming_k2k_mm_xrt
image_proc_adaptive image_pipeline_examples
ROS 2 Graph acceleration
perception_2nodes

ROS 2 Node acceleration examples

Package Acceleration kernel Description
publisher_xilinx This package contains a minimalistic publisher using a member function for evaluation purposes which subclasses rclcpp::Node and sets up an rclcpp::timer to periodically call functions which publish messages.
simple_adder adder1 adder2 A trivial adder example. No interactions with the ROS 2 computational graph. Meant to demonstrate how HLS is integrated into build ROS 2 flows.
vadd_publisher A a trivial vector-add ROS 2 publisher. Adds two inputs to a vector in a loop and tries publishing it on the go at 10 Hz.
doublevadd_publisher A trivial double vector-add ROS 2 publisher. Adds two inputs to a vector in a loop and publishes on the go at 10 Hz. Running in hardware shows that it's not able to meet the rate target and stays at around 2 Hz. The objective of this package is to generate a computationally expensive baseline when executed in a general purpose embedded CPU. See accelerated_doublevadd_publisher package for an optimized and accelerated version of the same package which offloads the vector operations into an FPGA. See faster_doublevadd_publisher for an even more optimized version.
offloaded_doublevadd_publisher vadd An offloaded version of the trivial doublevadd_publisher which adds two inputs to a vector in a loop and publishes them at 10 Hz. Vector add operations are directly offloaded into to the FPGA (i.e. a kernel is created out of C++, without any modifications). The offloading operation shows how while guaranteeing determinsm in the vadd operation context, simple offloading to the FPGA lowers the publishing rate from 2 Hz (in the CPU) to 1.5 Hz due the slower clock that the FPGA uses
accelerated_vadd_publisher vadd An dataflow optimized offloaded version of the trivial doublevadd_publisher ROS 2 publisher which adds two inputs to a vector in a loop and publishes them at 10 Hz. Vector add operations are offloaded into to the FPGA and some minor dataflow optimizations are applied using HLS. The offloading operation into the FPGA allows the publisher to go from 2 Hz to 6 Hz but, still misses its target (10 Hz)
faster_doublevadd_publisher vadd An accelerated version of the trivial doublevadd_publisher ROS 2 publisher which adds two inputs to a vector in a loop and publishes them at 10 Hz. Vector add operations are accelerated by exploiting parallelism with the FPGA. Also, similarly to accelerated_doublevadd_publisher, some basic dataflow optimizations are performed. The code parallelism and dataflow optimizations of the dataflow allows the publisher to go from 2 Hz to 10 Hz, meeting its target
multiple_doublevadd_publisher vadd_offloaded, vadd_accelerated, vadd_faster Smashes various acceleration kernels (coming from the previous doublevadd_publisher series) into a single hardware design (bitstream) that can then be used to program the FPGA, allowing to run various Nodes and their kernels simultaneously, without the need to reprogramm the FPGA.
streaming_k2k_mm_xrt krnl_stream_vadd, krnl_stream_vmult This example demonstrates how kernels can have memory mapped inputs along with stream interface from one kernel to another. Specifically, this is aROS native version of a simple kernel to kernelstreaming Vector Add and Vector Multiply C Kernel design with2 memory mapped input to kernel 1, 1 Stream output from kernel1 to input of kernel 2, 1 memory mapped input to kernel 2, and1 memory mapped output that demonstrates on how to process astream of data for computation between two kernels using XRTNative APIs. This design also illustrates how to set FIFO depthfor AXIS connections i.e. for the stream connecting the two kernels.
image_proc_adaptive An example that makes use of the ROS perception's image_pipeline3 meta-package to demonstrate how to make a ROS 2 adaptive Components that can run either in CPU or in the FPGA. Refer to adaptive_component for more details on a composable container for Adaptive ROS 2 Node computations.
image_pipeline_examples Provides Node wrappers to group together and demonstrate various combinations of hardware-accelerated perception pipelines using the image_pipeline3 package.
  • 1: measured with ros2 topic hz <topic-name>
  • 2: very low rate.
  • 3: we're using our fork. In time, we expect these changes to be merged upstream.

ROS 2 Graph acceleration examples

Package Acceleration kernel Description
perception_2nodes rectify_accel, resize_accel, rectify_resize_accel, rectify_accel_streamlined, resize_accel_streamlined, Demonstrates a simple perception computational graph composed by 2 dataflow-connected Nodes, rectify and resize. Package relies on image_pipeline3 Nodes and provides a series of launch automations that are used to demonstrate the value of accelerating the computational graph.

Quality Declaration

No quality is claimed according to REP-2004. This meta-package is designed as a learning and reference resource and it should not be used in production environments.