├── .gitignore ├── LICENSE ├── README.md ├── graphs └── perception │ ├── perception_2nodes │ ├── README.md │ ├── launch │ │ ├── analyse_rectify.launch.py │ │ ├── analyse_rectify_resize.launch.py │ │ ├── analyse_resize.launch.py │ │ ├── raw_rectify_resize.launch.py │ │ ├── rectify.launch.py │ │ ├── rectify_fpga.launch.py │ │ ├── resize.launch.py │ │ ├── resize_fpga.launch.py │ │ ├── simulated_rectify_resize.launch.py │ │ ├── simulation.launch.py │ │ ├── trace_raw_rectify_resize.launch.py │ │ ├── trace_rectify.launch.py │ │ ├── trace_rectify_fpga.launch.py │ │ ├── trace_rectify_resize.launch.py │ │ ├── trace_rectify_resize_fpga.launch.py │ │ ├── trace_rectify_resize_fpga_integrated.launch.py │ │ ├── trace_rectify_resize_fpga_integrated_node.launch.py │ │ ├── trace_rectify_resize_fpga_integrated_streamlined.launch.py │ │ ├── trace_rectify_resize_fpga_integrated_streamlined_xrt.launch.py │ │ ├── trace_rectify_resize_fpga_integrated_xrt.launch.py │ │ ├── trace_rectify_resize_fpga_streamlined.launch.py │ │ ├── trace_rectify_resize_fpga_streamlined_xrt.launch.py │ │ ├── trace_resize.launch.py │ │ └── trace_resize_fpga.launch.py │ ├── models │ │ └── camera-plugin │ │ │ ├── model.config │ │ │ ├── model_distorted.sdf │ │ │ └── model_undistorted.sdf │ ├── package.xml │ ├── perception_2nodes │ │ ├── __init__.py │ │ └── image_raw_publisher.py │ ├── resource │ │ ├── data │ │ │ ├── camera_info.json │ │ │ ├── image_raw.jpg │ │ │ ├── image_raw.json │ │ │ ├── opencv-1.jpg │ │ │ ├── opencv-10.jpg │ │ │ ├── opencv-11.jpg │ │ │ ├── opencv-12.jpg │ │ │ ├── opencv-13.jpg │ │ │ ├── opencv-14.jpg │ │ │ ├── opencv-15.jpg │ │ │ ├── opencv-16.jpg │ │ │ ├── opencv-17.jpg │ │ │ ├── opencv-18.jpg │ │ │ ├── opencv-19.jpg │ │ │ ├── opencv-2.jpg │ │ │ ├── opencv-20.jpg │ │ │ ├── opencv-21.jpg │ │ │ ├── opencv-22.jpg │ │ │ ├── opencv-23.jpg │ │ │ ├── opencv-24.jpg │ │ │ ├── opencv-25.jpg │ │ │ ├── opencv-26.jpg │ │ │ ├── opencv-27.jpg │ │ │ ├── opencv-28.jpg │ │ │ ├── opencv-29.jpg │ │ │ ├── opencv-3.jpg │ │ │ ├── opencv-30.jpg │ │ │ ├── opencv-31.jpg │ │ │ ├── opencv-32.jpg │ │ │ ├── opencv-33.jpg │ │ │ ├── opencv-34.jpg │ │ │ ├── opencv-35.jpg │ │ │ ├── opencv-36.jpg │ │ │ ├── opencv-37.jpg │ │ │ ├── opencv-38.jpg │ │ │ ├── opencv-39.jpg │ │ │ ├── opencv-4.jpg │ │ │ ├── opencv-40.jpg │ │ │ ├── opencv-41.jpg │ │ │ ├── opencv-42.jpg │ │ │ ├── opencv-43.jpg │ │ │ ├── opencv-44.jpg │ │ │ ├── opencv-45.jpg │ │ │ ├── opencv-46.jpg │ │ │ ├── opencv-47.jpg │ │ │ ├── opencv-48.jpg │ │ │ ├── opencv-49.jpg │ │ │ ├── opencv-5.jpg │ │ │ ├── opencv-50.jpg │ │ │ ├── opencv-51.jpg │ │ │ ├── opencv-52.jpg │ │ │ ├── opencv-53.jpg │ │ │ ├── opencv-54.jpg │ │ │ ├── opencv-55.jpg │ │ │ ├── opencv-56.jpg │ │ │ ├── opencv-57.jpg │ │ │ ├── opencv-58.jpg │ │ │ ├── opencv-59.jpg │ │ │ ├── opencv-6.jpg │ │ │ ├── opencv-60.jpg │ │ │ ├── opencv-61.jpg │ │ │ ├── opencv-62.jpg │ │ │ ├── opencv-63.jpg │ │ │ ├── opencv-64.jpg │ │ │ ├── opencv-65.jpg │ │ │ ├── opencv-66.jpg │ │ │ ├── opencv-67.jpg │ │ │ ├── opencv-68.jpg │ │ │ ├── opencv-69.jpg │ │ │ ├── opencv-7.jpg │ │ │ ├── opencv-70.jpg │ │ │ ├── opencv-71.jpg │ │ │ ├── opencv-72.jpg │ │ │ ├── opencv-73.jpg │ │ │ ├── opencv-74.jpg │ │ │ ├── opencv-75.jpg │ │ │ ├── opencv-76.jpg │ │ │ ├── opencv-77.jpg │ │ │ ├── opencv-78.jpg │ │ │ ├── opencv-79.jpg │ │ │ ├── opencv-8.jpg │ │ │ ├── opencv-80.jpg │ │ │ ├── opencv-81.jpg │ │ │ ├── opencv-82.jpg │ │ │ ├── opencv-83.jpg │ │ │ ├── opencv-84.jpg │ │ │ ├── opencv-85.jpg │ │ │ ├── opencv-86.jpg │ │ │ ├── opencv-87.jpg │ │ │ ├── opencv-88.jpg │ │ │ ├── opencv-89.jpg │ │ │ ├── opencv-9.jpg │ │ │ └── opencv-90.jpg │ │ └── perception_2nodes │ ├── setup.cfg │ ├── setup.py │ ├── test │ │ ├── test_copyright.py │ │ ├── test_flake8.py │ │ └── test_pep257.py │ └── worlds │ │ ├── camera.world │ │ ├── camera_dynamic.world │ │ ├── camera_dynamic_hd.world │ │ ├── camera_dynamic_undistorted.world │ │ └── camera_simple.world │ └── perception_3nodes │ ├── CMakeLists.txt │ ├── cfg │ └── kv260_perception_3nodes.cfg │ ├── include │ ├── harris.hpp │ ├── harris_fpga.hpp │ ├── integrated_fpga.hpp │ ├── rectify_fpga.hpp │ ├── resize_fpga.hpp │ └── xf_ocv_ref.hpp │ ├── launch │ ├── analyse_perception_3nodes.launch.py │ ├── trace_perception_3nodes.launch.py │ └── trace_perception_3nodes_fpga.launch.py │ ├── package.xml │ └── src │ ├── harris.cpp │ ├── harris_fpga.cpp │ ├── integrated_fpga.cpp │ ├── kernels │ ├── xf_harris_accel.cpp │ ├── xf_rectify_accel.cpp │ └── xf_resize_accel.cpp │ ├── perception_3nodes.cpp │ ├── perception_3nodes_fpga.cpp │ ├── perception_3nodes_gpu.cpp │ ├── rectify_fpga.cpp │ └── resize_fpga.cpp ├── nodes ├── accelerated_doublevadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ ├── ZTS11VectorAddID_register_map.hpp │ │ ├── avalonmm_driver.hpp │ │ ├── exception_handler.hpp │ │ └── vadd.hpp │ ├── package.xml │ └── src │ │ ├── accelerated_doublevadd_publisher.cpp │ │ ├── accelerated_doublevadd_publisher_agilex.cpp │ │ ├── avalonmm_driver.cpp │ │ ├── doublevadd_oneapi.cpp │ │ ├── kernel_driver.cpp │ │ ├── kv260.cfg │ │ ├── sadd.cpp │ │ ├── sed_sadd_user_subsystem.tcl │ │ ├── sed_vadd_user_subsystem.tcl │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── accelerated_vadd │ ├── CMakeLists.txt │ ├── package.xml │ └── src │ │ ├── host.cpp │ │ ├── host_new.cpp │ │ ├── kv260.cfg │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── accelerated_vadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ ├── exception_handler.hpp │ │ └── vadd.hpp │ ├── launch │ │ ├── accelerated_vadd_analyse.launch.py │ │ ├── accelerated_vadd_capture_agilex.launch.py │ │ ├── accelerated_vadd_power_analyse.launch.py │ │ └── accelerated_vadd_power_tracing.launch.py │ ├── package.xml │ └── src │ │ ├── accelerated_vadd_publisher_agilex.cpp │ │ ├── sed_vadd_user_subsystem.tcl │ │ └── vadd_oneapi.cpp ├── accelerated_vadd_publisher_once │ ├── CMakeLists.txt │ ├── COLCON_IGNORE │ ├── include │ │ └── vadd.hpp │ ├── package.xml │ └── src │ │ ├── accelerated_vadd_publisher_once.cpp │ │ ├── kv260.cfg │ │ ├── testbench_vadd.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── doublevadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ ├── doublevadd_component.hpp │ │ ├── doublevadd_component_adaptive.hpp │ │ ├── doublevadd_component_adaptive_stateful.hpp │ │ ├── doublevadd_component_fpga.hpp │ │ ├── doublevadd_component_typeadapter.hpp │ │ └── vadd.hpp │ ├── launch │ │ ├── vadd_analyse.launch.py │ │ ├── vadd_capture.launch.py │ │ ├── vadd_power_analyse.launch.py │ │ └── vadd_power_tracing.launch.py │ ├── package.xml │ ├── scripts │ │ └── trace_analysis_vaddtiming.py │ └── src │ │ ├── doublevadd_component.cpp │ │ ├── doublevadd_component_adaptive.cpp │ │ ├── doublevadd_component_adaptive_stateful.cpp │ │ ├── doublevadd_component_fpga.cpp │ │ ├── doublevadd_component_typeadapter.cpp │ │ ├── doublevadd_node.cpp │ │ ├── doublevadd_node_adaptive.cpp │ │ ├── doublevadd_publisher.cpp │ │ ├── doublevadd_publisher_adaptive.cpp │ │ ├── doublevadd_publisher_adaptive_with_components.cpp │ │ ├── doublevadd_publisher_adaptive_with_components_and_state.cpp │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── faster_doublevadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ └── vadd.hpp │ ├── launch │ │ ├── vadd_analyse.launch.py │ │ ├── vadd_analyse_slx.launch.py │ │ └── vadd_capture.launch.py │ ├── package.xml │ └── src │ │ ├── faster_doublevadd.cpp │ │ ├── faster_doublevadd_publisher.cpp │ │ ├── kv260.cfg │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ ├── vadd_dataflow.cpp │ │ ├── vadd_faster.dtbo.new │ │ ├── vadd_faster.dtsi │ │ ├── vadd_slx.cpp │ │ └── zcu102.cfg ├── faster_triplevadd_publisher │ ├── CMakeLists.txt │ ├── COLCON_IGNORE │ ├── include │ │ └── vadd.hpp │ ├── package.xml │ └── src │ │ ├── faster_triplevadd.cpp │ │ ├── faster_triplevadd_publisher.cpp │ │ ├── kv260.cfg │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ ├── vadd_dataflow.cpp │ │ └── zcu102.cfg ├── image_pipeline_examples │ ├── CMakeLists.txt │ ├── launch │ │ ├── rectify_resize.launch.py │ │ ├── trace_rectify.launch.py │ │ └── trace_rectify_resize_gpu.launch.py │ ├── package.xml │ └── src │ │ ├── rectify_node.cpp │ │ ├── rectify_resize_fpga_integrated_node.cpp │ │ ├── rectify_resize_fpga_integrated_streamlined_node.cpp │ │ ├── rectify_resize_fpga_node.cpp │ │ ├── rectify_resize_fpga_streamlined_node.cpp │ │ ├── rectify_resize_fpga_streamlined_node_xrt.cpp │ │ ├── rectify_resize_gpu_node.cpp │ │ └── rectify_resize_node.cpp ├── image_proc_adaptive │ ├── CMakeLists.txt │ ├── include │ │ └── image_proc_adaptive.hpp │ ├── launch │ │ └── image_proc_adaptive.launch.py │ ├── package.xml │ └── src │ │ ├── image_proc_adaptive.cpp │ │ ├── image_proc_node_adaptive.cpp │ │ └── kv260.cfg ├── multiple_doublevadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ └── vadd.hpp │ ├── launch │ │ └── all.launch.py │ ├── package.xml │ └── src │ │ ├── accelerated_doublevadd_publisher.cpp │ │ ├── faster_doublevadd_publisher.cpp │ │ ├── kv260.cfg │ │ ├── kv260_multiple.cfg │ │ ├── offloaded_doublevadd_publisher.cpp │ │ ├── vadd_accelerated.cpp │ │ ├── vadd_faster.cpp │ │ └── vadd_offloaded.cpp ├── offloaded_doublevadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ └── vadd.hpp │ ├── package.xml │ └── src │ │ ├── kv260.cfg │ │ ├── offloaded_doublevadd_publisher.cpp │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── publisher_xilinx │ ├── CMakeLists.txt │ ├── launch │ │ └── trace.launch.py │ ├── member_function_publisher.cpp │ └── package.xml ├── simple_adder │ ├── CMakeLists.txt │ ├── imgs │ │ ├── 1.png │ │ ├── 2.png │ │ ├── 3.png │ │ ├── 4.png │ │ ├── 5.png │ │ └── 6.png │ ├── include │ │ └── adder.hpp │ ├── package.xml │ └── src │ │ ├── adder1.cpp │ │ ├── adder2.cpp │ │ ├── kv260.cfg │ │ ├── testbench1.cpp │ │ ├── testbench2.cpp │ │ └── zcu102.cfg ├── simple_vadd │ ├── CMakeLists.txt │ ├── README.md │ ├── package.xml │ └── src │ │ ├── krnl_vadd.cpp │ │ ├── kv260.cfg │ │ ├── vadd.cpp │ │ └── vadd.h ├── triplevadd_publisher │ ├── CMakeLists.txt │ ├── COLCON_IGNORE │ ├── include │ │ └── vadd.hpp │ ├── package.xml │ └── src │ │ ├── testbench.cpp │ │ ├── triplevadd_publisher.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ └── zcu102.cfg ├── vadd_publisher │ ├── CMakeLists.txt │ ├── include │ │ └── vadd.hpp │ ├── launch │ │ ├── vadd_analyse.launch.py │ │ ├── vadd_capture.launch.py │ │ ├── vadd_power_analyse.launch.py │ │ └── vadd_power_tracing.launch.py │ ├── package.xml │ └── src │ │ ├── testbench.cpp │ │ ├── u200.cfg │ │ ├── vadd.cpp │ │ ├── vadd_publisher.cpp │ │ └── zcu102.cfg └── xrt_examples │ └── streaming_k2k_mm_xrt │ ├── CMakeLists.txt │ ├── include │ ├── cmdlineparser.h │ └── logger.h │ ├── package.xml │ └── src │ ├── cmdlineparser.cpp │ ├── host.cpp │ ├── krnl_stream_vadd.cpp │ ├── krnl_stream_vadd_vmult.cfg │ ├── krnl_stream_vmult.cpp │ └── logger.cpp └── vitis_accelerated_examples ├── vitis_accelerated_resize ├── CMakeLists.txt ├── cfg │ └── kr260.cfg ├── include │ ├── minimalimagepublisher.hpp │ ├── resize_fpga.hpp │ └── xf_resize_config.h ├── package.xml └── src │ ├── main.cpp │ ├── resize_fpga.cpp │ └── xf_resize_accel.cpp └── vitis_accelerated_stereolbm ├── CMakeLists.txt ├── cfg └── kr260.cfg ├── data ├── left.png └── right.png ├── include ├── accelerated_node.hpp ├── minimalimagepublisher.hpp ├── xf_config_params.h └── xf_stereolbm_config.h ├── package.xml └── src ├── accelerated_node.cpp ├── main.cpp └── xf_stereolbm_accel.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | .DS_Store 2 | __pycache__ 3 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/launch/rectify.launch.py: -------------------------------------------------------------------------------- 1 | """RectifyNode and RectifyNodeFPGA components launch file.""" 2 | 3 | import pytest 4 | import launch 5 | import rclpy 6 | from rclpy.node import Node 7 | from std_msgs.msg import String 8 | from sensor_msgs.msg import CameraInfo, Image 9 | from launch_ros.actions import Node 10 | from launch_ros.actions import ComposableNodeContainer, Node 11 | from launch_ros.descriptions import ComposableNode 12 | 13 | 14 | def generate_launch_description(): 15 | """Generate launch description with multiple components.""" 16 | 17 | # # An image_raw publisher 18 | # image_raw_publisher = Node( 19 | # package="perception_2nodes", 20 | # executable="image_raw_publisher", 21 | # name="image_raw_publisher", 22 | # # remappings=[("image_raw", "image")], 23 | # ) 24 | 25 | rectify_container = ComposableNodeContainer( 26 | name="rectify_container", 27 | namespace="", 28 | package="rclcpp_components", 29 | executable="component_container", 30 | composable_node_descriptions=[ 31 | # ComposableNode( 32 | # package="image_proc", 33 | # plugin="image_proc::RectifyNodeFPGA", 34 | # name="rectify_node_fpga", 35 | # remappings=[("image", "image_raw")], 36 | # ), 37 | ComposableNode( 38 | package="image_proc", 39 | plugin="image_proc::RectifyNode", 40 | name="rectify_node", 41 | # remappings=[("image", "image_raw")], # for image_raw_publisher 42 | remappings=[ 43 | ("image", "/camera/image_raw"), 44 | ("camera_info", "/camera/camera_info"), 45 | ], 46 | ), 47 | ], 48 | output="screen", 49 | ) 50 | 51 | 52 | 53 | # return launch.LaunchDescription([image_raw_publisher]) 54 | return launch.LaunchDescription([rectify_container]) 55 | # return launch.LaunchDescription([image_raw_publisher, rectify_container]) 56 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/launch/resize.launch.py: -------------------------------------------------------------------------------- 1 | """ResizeNode and ResizeNodeFPGA components launch file.""" 2 | import pytest 3 | import launch 4 | import rclpy 5 | from rclpy.node import Node 6 | from std_msgs.msg import String 7 | from sensor_msgs.msg import CameraInfo, Image 8 | from launch_ros.actions import Node 9 | from launch_ros.actions import ComposableNodeContainer, Node 10 | from launch_ros.descriptions import ComposableNode 11 | 12 | 13 | # @pytest.mark.rostest 14 | def generate_launch_description(): 15 | """Generate launch description with multiple components.""" 16 | 17 | # # An image_raw publisher 18 | # image_raw_publisher = Node( 19 | # package="perception_2nodes", 20 | # executable="image_raw_publisher", 21 | # name="image_raw_publisher", 22 | # # remappings=[("image_raw", "image")], 23 | # ) 24 | 25 | resize_container = ComposableNodeContainer( 26 | name="resize_container", 27 | namespace="", 28 | package="rclcpp_components", 29 | executable="component_container", 30 | composable_node_descriptions=[ 31 | ComposableNode( 32 | package="image_proc", 33 | plugin="image_proc::ResizeNode", 34 | name="resize_node", 35 | # remappings=[("image", "image_raw")], # image_raw_publisher 36 | remappings=[ 37 | ("image", "/camera/image_raw"), 38 | ("camera_info", "/camera/camera_info"), 39 | ], 40 | parameters=[ 41 | { 42 | "scale_height": 2.0, 43 | "scale_width": 2.0, 44 | } 45 | ], 46 | ), 47 | ], 48 | output="screen", 49 | ) 50 | return launch.LaunchDescription([resize_container]) 51 | # return launch.LaunchDescription([image_raw_publisher, resize_container]) 52 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/launch/resize_fpga.launch.py: -------------------------------------------------------------------------------- 1 | """ResizeNode and ResizeNodeFPGA components launch file.""" 2 | import pytest 3 | import launch 4 | import rclpy 5 | from rclpy.node import Node 6 | from std_msgs.msg import String 7 | from sensor_msgs.msg import CameraInfo, Image 8 | from launch_ros.actions import Node 9 | from launch_ros.actions import ComposableNodeContainer, Node 10 | from launch_ros.descriptions import ComposableNode 11 | 12 | 13 | # @pytest.mark.rostest 14 | def generate_launch_description(): 15 | """Generate launch description with multiple components.""" 16 | 17 | # # An image_raw publisher 18 | # image_raw_publisher = Node( 19 | # package="perception_2nodes", 20 | # executable="image_raw_publisher", 21 | # name="image_raw_publisher", 22 | # # remappings=[("image_raw", "image")], 23 | # ) 24 | 25 | resize_container = ComposableNodeContainer( 26 | name="resize_container", 27 | namespace="", 28 | package="rclcpp_components", 29 | executable="component_container", 30 | composable_node_descriptions=[ 31 | ComposableNode( 32 | package="image_proc", 33 | plugin="image_proc::ResizeNodeFPGA", 34 | name="resize_node_fpga", 35 | # remappings=[("image", "image_raw")], # image_raw_publisher 36 | remappings=[ 37 | ("image", "/camera/image_raw"), 38 | ("camera_info", "/camera/camera_info"), 39 | ], 40 | parameters=[ 41 | { 42 | "scale_height": 2.0, 43 | "scale_width": 2.0, 44 | } 45 | ], 46 | ), 47 | ], 48 | output="screen", 49 | ) 50 | return launch.LaunchDescription([resize_container]) 51 | # return launch.LaunchDescription([image_raw_publisher, resize_container]) 52 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/models/camera-plugin/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Camera-plugin 5 | 1.0 6 | model_distorted.sdf 7 | 8 | 9 | 10 | Víctor Mayoral-Vilches 11 | victorma@xilinx.com 12 | 13 | 14 | 15 | A simple 640x480 camera with a chessboard and a box for visualization, with a ROS plugin 16 | 17 | 18 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/models/camera-plugin/model_distorted.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 0.05 0.05 0.05 0 0 0 6 | 7 | 0.1 8 | 9 | 0.000166667 10 | 0.000166667 11 | 0.000166667 12 | 13 | 14 | 15 | 16 | 17 | 0.1 0.1 0.1 18 | 19 | 20 | 21 | 22 | 23 | 24 | 0.1 0.1 0.1 25 | 26 | 27 | 28 | 29 | 30 | 1.047 31 | 32 | 640 33 | 480 34 | 35 | 36 | 0.1 37 | 100 38 | 39 | 40 | -0.25 41 | 0.12 42 | 0.0 43 | -0.00028 44 | -0.00005 45 |
0.5 0.5
46 |
47 |
48 | 1 49 | 30 50 | true 51 |
52 | 53 |
54 |
55 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/models/camera-plugin/model_undistorted.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 0.05 0.05 0.05 0 0 0 6 | 7 | 0.1 8 | 9 | 0.000166667 10 | 0.000166667 11 | 0.000166667 12 | 13 | 14 | 15 | 16 | 17 | 0.1 0.1 0.1 18 | 19 | 20 | 21 | 22 | 23 | 24 | 0.1 0.1 0.1 25 | 26 | 27 | 28 | 29 | 30 | 1.047 31 | 32 | 640 33 | 480 34 | 35 | 36 | 0.1 37 | 100 38 | 39 | 40 | 0 41 | 0 42 | 0.0 43 | 0.0 44 | 0.0 45 |
0.5 0.5
46 |
47 |
48 | 1 49 | 30 50 | true 51 |
52 | 53 |
54 |
55 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | perception_2nodes 5 | 0.3.0 6 | 7 | A simple perception computational graph composed by 2 Nodes. 8 | Used to demonstrate the value of accelerating image_pipeline 9 | computational graphs. 10 | 11 | Víctor Mayoral-Vilches 12 | Apache License 2.0 13 | 14 | image_proc 15 | rclpy 16 | std_msgs 17 | 18 | 20 | ament_copyright 21 | ament_flake8 22 | ament_pep257 23 | python3-pytest 24 | 25 | 26 | ament_python 27 | 28 | 29 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/perception_2nodes/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/perception_2nodes/__init__.py -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/camera_info.json: -------------------------------------------------------------------------------- 1 | { 2 | "header": { 3 | "frame_id": "tf_camera" 4 | }, 5 | "width": 640, 6 | "height": 480, 7 | "distortion_model": "plumb_bob", 8 | "D": [ 9 | -0.3055922322256572, 10 | 0.1327657254931037, 11 | 0.0010529200006077347, 12 | 0.0007537770371342291, 13 | 0.0 14 | ], 15 | "K": [ 16 | 539.8853193064406, 17 | 0.0, 18 | 290.0347382015241, 19 | 0.0, 20 | 539.3911641902295, 21 | 267.2787858937308, 22 | 0.0, 23 | 0.0, 24 | 1.0 25 | ], 26 | "R": [ 27 | 1.0, 28 | 0.0, 29 | 0.0, 30 | 0.0, 31 | 1.0, 32 | 0.0, 33 | 0.0, 34 | 0.0, 35 | 1.0 36 | ], 37 | "P": [ 38 | 478.7103271484375, 0.0, 283.5353321156799, 0.0, 0.0, 502.72369384765625, 270.741585324231, 0.0, 0.0, 0.0, 1.0, 0.0 39 | ] 40 | } 41 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/image_raw.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/image_raw.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/image_raw.json: -------------------------------------------------------------------------------- 1 | { 2 | "image": "image_raw.jpg", 3 | "encoding": "bgr8", 4 | "chessboard": { 5 | "width": 9, 6 | "height": 6 7 | } 8 | } 9 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-1.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-10.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-10.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-11.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-11.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-12.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-12.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-13.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-13.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-14.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-14.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-15.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-15.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-16.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-16.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-17.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-17.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-18.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-18.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-19.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-19.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-2.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-20.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-20.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-21.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-21.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-22.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-22.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-23.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-23.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-24.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-24.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-25.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-25.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-26.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-26.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-27.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-27.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-28.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-28.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-29.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-29.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-3.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-3.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-30.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-30.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-31.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-31.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-32.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-32.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-33.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-33.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-34.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-34.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-35.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-35.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-36.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-36.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-37.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-37.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-38.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-38.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-39.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-39.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-4.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-4.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-40.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-40.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-41.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-41.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-42.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-42.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-43.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-43.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-44.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-44.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-45.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-45.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-46.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-46.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-47.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-47.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-48.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-48.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-49.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-49.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-5.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-5.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-50.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-50.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-51.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-51.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-52.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-52.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-53.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-53.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-54.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-54.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-55.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-55.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-56.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-56.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-57.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-57.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-58.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-58.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-59.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-59.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-6.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-6.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-60.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-60.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-61.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-61.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-62.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-62.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-63.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-63.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-64.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-64.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-65.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-65.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-66.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-66.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-67.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-67.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-68.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-68.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-69.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-69.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-7.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-7.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-70.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-70.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-71.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-71.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-72.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-72.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-73.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-73.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-74.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-74.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-75.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-75.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-76.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-76.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-77.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-77.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-78.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-78.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-79.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-79.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-8.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-8.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-80.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-80.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-81.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-81.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-82.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-82.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-83.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-83.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-84.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-84.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-85.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-85.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-86.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-86.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-87.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-87.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-88.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-88.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-89.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-89.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-9.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-9.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/data/opencv-90.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/data/opencv-90.jpg -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/resource/perception_2nodes: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/graphs/perception/perception_2nodes/resource/perception_2nodes -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/setup.cfg: -------------------------------------------------------------------------------- 1 | [develop] 2 | script_dir=$base/lib/perception_2nodes 3 | [install] 4 | install_scripts=$base/lib/perception_2nodes 5 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import setup 2 | import os 3 | from glob import glob 4 | 5 | 6 | package_name = "perception_2nodes" 7 | setup( 8 | name=package_name, 9 | version="0.1.0", 10 | packages=[package_name], 11 | data_files=[ 12 | ("share/ament_index/resource_index/packages", ["resource/" + package_name]), 13 | ("share/" + package_name, ["package.xml"]), 14 | ("share/" + package_name + "/launch", glob("launch/*.launch.py")), 15 | ( 16 | "share/" + package_name + "/resource/data", 17 | glob("resource/data/*"), 18 | ), 19 | ("share/" + package_name + "/worlds", glob("worlds/*.world")), 20 | ("share/" + package_name + "/models/camera-plugin", glob("models/camera-plugin/*")), 21 | ], 22 | install_requires=["setuptools"], 23 | zip_safe=True, 24 | author="Víctor Mayoral-Vilches", 25 | author_email="v.mayoralv@gmail.com", 26 | maintainer="Víctor Mayoral-Vilches", 27 | maintainer_email="v.mayoralv@gmail.com", 28 | keywords=["ROS"], 29 | classifiers=[ 30 | "Intended Audience :: Developers", 31 | "License :: OSI Approved :: Apache Software License", 32 | "Programming Language :: Python", 33 | "Topic :: Software Development", 34 | ], 35 | description="A simple perception computational graph composed by 2 Nodes.", 36 | license="Apache License, Version 2.0", 37 | tests_require=["pytest"], 38 | entry_points={ 39 | "console_scripts": [ 40 | "image_raw_publisher = perception_2nodes.image_raw_publisher:main", 41 | ], 42 | }, 43 | ) 44 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=["."]) 23 | assert rc == 0, "Found errors" 24 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=['.']) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /graphs/perception/perception_2nodes/worlds/camera_simple.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | model://sun 8 | 9 | 10 | 11 | 12 | model://ground_plane 13 | 0 0 0 0 0 0 14 | 15 | 16 | 17 | 18 | 19 | 0.556 -0.9132 0.8266 0 0.59 2.15 20 | 21 | 22 | 23 | 24 | 25 | model://camera-plugin 26 | 0 -0.07266 0.3 0 1.1 0 27 | 1 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /graphs/perception/perception_3nodes/cfg/kv260_perception_3nodes.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | [clock] 10 | freqHz=250000000:rectify_accel_streamlined_1 11 | freqHz=250000000:resize_accel_streamlined_1 12 | freqHz=250000000:cornerHarris_accel_1 13 | 14 | [connectivity] 15 | stream_connect=rectify_accel_streamlined_1.img_out:resize_accel_streamlined_1.img_inp:64 16 | stream_connect=resize_accel_streamlined_1.img_out:cornerHarris_accel_1.img_inp:64 17 | -------------------------------------------------------------------------------- /graphs/perception/perception_3nodes/src/perception_3nodes.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2022 Víctor Mayoral-Vilches 2 | // All rights reserved. 3 | 4 | // Licensed under the Apache License, Version 2.0 (the "License"); 5 | // you may not use this file except in compliance with the License. 6 | // You may obtain a copy of the License at 7 | 8 | // http://www.apache.org/licenses/LICENSE-2.0 9 | 10 | // Unless required by applicable law or agreed to in writing, software 11 | // distributed under the License is distributed on an "AS IS" BASIS, 12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | // See the License for the specific language governing permissions and 14 | // limitations under the License. 15 | 16 | #include 17 | #include "image_proc/rectify.hpp" 18 | #include "image_proc/resize.hpp" 19 | #include "harris.hpp" 20 | #include "rclcpp/rclcpp.hpp" 21 | 22 | int main(int argc, char * argv[]) 23 | { 24 | rclcpp::init(argc, argv); 25 | 26 | rclcpp::executors::SingleThreadedExecutor exec; 27 | // rclcpp::executors::MultiThreadedExecutor exec; 28 | 29 | rclcpp::NodeOptions options; 30 | auto rectify_node = 31 | std::make_shared(options); 32 | auto resize_node = 33 | std::make_shared(options); 34 | auto harris_node = 35 | std::make_shared(options); 36 | 37 | exec.add_node(rectify_node); 38 | exec.add_node(resize_node); 39 | exec.add_node(harris_node); 40 | 41 | exec.spin(); 42 | rclcpp::shutdown(); 43 | return 0; 44 | } 45 | -------------------------------------------------------------------------------- /graphs/perception/perception_3nodes/src/perception_3nodes_fpga.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2022 Víctor Mayoral-Vilches 2 | // All rights reserved. 3 | 4 | // Licensed under the Apache License, Version 2.0 (the "License"); 5 | // you may not use this file except in compliance with the License. 6 | // You may obtain a copy of the License at 7 | 8 | // http://www.apache.org/licenses/LICENSE-2.0 9 | 10 | // Unless required by applicable law or agreed to in writing, software 11 | // distributed under the License is distributed on an "AS IS" BASIS, 12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | // See the License for the specific language governing permissions and 14 | // limitations under the License. 15 | 16 | #include 17 | #include "rclcpp/rclcpp.hpp" 18 | #include "harris_fpga.hpp" 19 | #include "rectify_fpga.hpp" 20 | #include "resize_fpga.hpp" 21 | 22 | int main(int argc, char * argv[]) 23 | { 24 | rclcpp::init(argc, argv); 25 | 26 | // rclcpp::executors::SingleThreadedExecutor exec; 27 | rclcpp::executors::MultiThreadedExecutor exec; 28 | 29 | rclcpp::NodeOptions options; 30 | auto rectify_node = 31 | std::make_shared(options); 32 | auto resize_node = 33 | std::make_shared(options); 34 | auto harris_node = 35 | std::make_shared(options); 36 | 37 | exec.add_node(rectify_node); 38 | exec.add_node(resize_node); 39 | exec.add_node(harris_node); 40 | 41 | exec.spin(); 42 | rclcpp::shutdown(); 43 | return 0; 44 | } 45 | -------------------------------------------------------------------------------- /graphs/perception/perception_3nodes/src/perception_3nodes_gpu.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2022 Víctor Mayoral-Vilches 2 | // All rights reserved. 3 | 4 | // Licensed under the Apache License, Version 2.0 (the "License"); 5 | // you may not use this file except in compliance with the License. 6 | // You may obtain a copy of the License at 7 | 8 | // http://www.apache.org/licenses/LICENSE-2.0 9 | 10 | // Unless required by applicable law or agreed to in writing, software 11 | // distributed under the License is distributed on an "AS IS" BASIS, 12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | // See the License for the specific language governing permissions and 14 | // limitations under the License. 15 | 16 | #include 17 | #include "isaac_ros_image_proc/rectify_node.hpp" 18 | #include "isaac_ros_image_proc/resize_node.hpp" 19 | #include "rclcpp/rclcpp.hpp" 20 | 21 | int main(int argc, char * argv[]) 22 | { 23 | rclcpp::init(argc, argv); 24 | 25 | rclcpp::executors::SingleThreadedExecutor exec; 26 | // rclcpp::executors::MultiThreadedExecutor exec; 27 | rclcpp::NodeOptions options; 28 | 29 | auto rectify_node = 30 | std::make_shared(options); 31 | auto resize_node = 32 | std::make_shared(options); 33 | exec.add_node(rectify_node); 34 | exec.add_node(resize_node); 35 | 36 | exec.spin(); 37 | rclcpp::shutdown(); 38 | return 0; 39 | } 40 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/include/avalonmm_driver.hpp: -------------------------------------------------------------------------------- 1 | #ifndef AVALONMM_DRIVER_HPP 2 | #define AVALONMM_DRIVER_HPP 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | class AvalonMM_Driver { 10 | private: 11 | uintptr_t MMIO_BASE_ADDRESS; 12 | size_t MMIO_REGION_SIZE; 13 | int fd; 14 | volatile uint64_t *mmio_region; 15 | 16 | void write_register(uint32_t offset, uint64_t value); 17 | void ensure_mmio_mapped(); 18 | void cleanup_mmio(); 19 | 20 | public: 21 | AvalonMM_Driver(uintptr_t baseAddress, size_t regionSize); 22 | 23 | uint64_t read_register(uint32_t offset); 24 | void set_arg(uintptr_t register_addr, uint32_t memory_offset, int* values, size_t length); 25 | void get_arg(uint32_t memory_offset, int* values, size_t length); 26 | void start_kernel(uint32_t status_reg, uint64_t go_mask); 27 | bool is_kernel_done(uint32_t status_reg, uint64_t done_mask); 28 | int get_value(uint32_t offset); 29 | void set_value(uint32_t offset, int value); 30 | void dump_arg_values(uint32_t offset, size_t length); 31 | ~AvalonMM_Driver(); 32 | }; 33 | 34 | #endif // AVALONMM_DRIVER_HPP 35 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/include/exception_handler.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __EXCEPTIONHANDLER_HPP__ 2 | #define __EXCEPTIONHANDLER_HPP__ 3 | #include 4 | #include 5 | #include 6 | 7 | namespace fpga_tools { 8 | 9 | void exception_handler(sycl::exception_list exceptions) { 10 | for (std::exception_ptr const &e : exceptions) { 11 | try { 12 | std::rethrow_exception(e); 13 | } catch (sycl::exception const &e) { 14 | std::cout << "Caught asynchronous SYCL exception:\n" 15 | << e.what() << std::endl; 16 | } 17 | } 18 | } 19 | 20 | } // namespace fpga_tools 21 | 22 | #endif //__EXCEPTIONHANDLER_HPP__ 23 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd_accelerated( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | # [hls] 10 | # clock=300000000:vadd_accelerated 11 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/src/testbench.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include // NOLINT 17 | #include 18 | #include 19 | #include 20 | 21 | #include "vadd.hpp" 22 | 23 | #define DATA_SIZE 4096 // 2**12 24 | // #define DATA_SIZE 16384 // 2**14 25 | // #define DATA_SIZE 65536 // 2**16 26 | // #define DATA_SIZE 262144 // 2**18 27 | 28 | // using namespace std::chrono_literals; // NOLINT 29 | 30 | bool check_vadd( 31 | const unsigned int *in1, // Read-Only Vector 1 32 | const unsigned int *in2, // Read-Only Vector 2 33 | const unsigned int *out // Read-Only Result 34 | ) { 35 | bool match = true; 36 | // no need to iterate twice through the loop, math's the same 37 | for (int i = 0 ; i < DATA_SIZE ; i++) { 38 | unsigned int expected = in1[i]+in2[i]; 39 | if (out[i] != expected) { 40 | // std::cout << "Error: Result mismatch" << std::endl; 41 | // std::cout << "i = " << i << " CPU result = " 42 | // << expected << " Device result = " << out[i] << std::endl; 43 | match = false; 44 | break; 45 | } 46 | } 47 | return match; 48 | } 49 | 50 | int main(int argc, char * argv[]) { 51 | 52 | // Application variables 53 | unsigned int in1[DATA_SIZE]; 54 | unsigned int in2[DATA_SIZE]; 55 | unsigned int out[DATA_SIZE]; 56 | 57 | // randomize the vectors used 58 | for (int i = 0 ; i < DATA_SIZE ; i++) { 59 | in1[i] = rand() % DATA_SIZE; // NOLINT 60 | in2[i] = rand() % DATA_SIZE; // NOLINT 61 | out[i] = 0; 62 | } 63 | 64 | // Add vectors 65 | vadd_accelerated(in1, in2, out, DATA_SIZE); // function subject to be accelerated 66 | 67 | // Validate operation 68 | check_vadd(in1, in2, out); 69 | 70 | return 0; 71 | } 72 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_accelerated( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j < size; ++j) { // stupidly iterate over 34 | // it to generate load 35 | #pragma HLS loop_tripcount min = c_size max = c_size 36 | for (int i = 0; i < size; ++i) { 37 | #pragma HLS loop_tripcount min = c_size max = c_size 38 | out[i] = in1[i] + in2[i]; 39 | } 40 | } 41 | } 42 | } 43 | -------------------------------------------------------------------------------- /nodes/accelerated_doublevadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(accelerated_vadd) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(Threads REQUIRED) 15 | find_package(ament_vitis) 16 | 17 | # add_executable(accelerated_vadd_new 18 | # src/host_new.cpp) 19 | # target_include_directories(accelerated_vadd_new PUBLIC include) 20 | # target_link_libraries(accelerated_vadd_new 21 | # ${OpenCL_LIBRARY} 22 | # pthread) 23 | 24 | if (ROS_VITIS) 25 | find_package(vitis_common REQUIRED) 26 | find_package(OpenCL REQUIRED) 27 | 28 | # accelerated_vadd 29 | add_executable(accelerated_vadd 30 | src/host.cpp 31 | ) 32 | target_include_directories(accelerated_vadd PUBLIC include) 33 | target_link_libraries(accelerated_vadd 34 | ${OpenCL_LIBRARY} 35 | pthread 36 | ) 37 | ament_target_dependencies(accelerated_vadd 38 | vitis_common 39 | ) 40 | 41 | # vadd kernel 42 | vitis_acceleration_kernel( 43 | NAME vadd 44 | FILE src/vadd.cpp 45 | CONFIG src/kv260.cfg 46 | CLOCK 100000000:vadd 47 | INCLUDE 48 | include 49 | TYPE 50 | # sw_emu 51 | # hw_emu 52 | hw 53 | LINK 54 | PACKAGE 55 | ) 56 | 57 | install(TARGETS 58 | accelerated_vadd 59 | # accelerated_vadd_new 60 | DESTINATION lib/${PROJECT_NAME} 61 | ) 62 | endif() # ROS_VITIS 63 | 64 | ament_package() 65 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | accelerated_vadd 5 | 0.3.0 6 | A trivial vector-add example (NO ROS USED) that serves 7 | as a baseline for development and debugging. The computation 8 | sends two integer vectors and adds them. 9 | 10 | Vector add operations are offloaded into to the FPGA. The offloading 11 | operation into the FPGA (or to the Programmable Logic (PL)). 12 | 13 | Víctor Mayoral Vilches 14 | Apache License 2.0 15 | Víctor Mayoral Vilches 16 | 17 | ament_cmake 18 | ament_vitis 19 | 20 | acceleration_firmware_kv260 21 | vitis_common 22 | 23 | acceleration_firmware_kv260 24 | 25 | ament_lint_auto 26 | ament_lint_common 27 | 28 | 29 | ament_cmake 30 | 31 | 32 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | # [hls] 10 | # clock=300000000:vadd_accelerated 11 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | extern "C" { 18 | void vadd( 19 | const unsigned int *in1, // Read-Only Vector 1 20 | const unsigned int *in2, // Read-Only Vector 2 21 | unsigned int *out, // Output Result 22 | int size // Size in integer 23 | ) 24 | { 25 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 26 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 27 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 28 | 29 | for (int j = 0; j < size; ++j) { // stupidly iterate over 30 | // it to generate load 31 | for (int i = 0; i < size; ++i) { 32 | out[i] = in1[i] + in2[i]; 33 | } 34 | } 35 | } 36 | } 37 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher/include/exception_handler.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __EXCEPTIONHANDLER_HPP__ 2 | #define __EXCEPTIONHANDLER_HPP__ 3 | #include 4 | #include 5 | #include 6 | 7 | namespace fpga_tools { 8 | 9 | void exception_handler(sycl::exception_list exceptions) { 10 | for (std::exception_ptr const &e : exceptions) { 11 | try { 12 | std::rethrow_exception(e); 13 | } catch (sycl::exception const &e) { 14 | std::cout << "Caught asynchronous SYCL exception:\n" 15 | << e.what() << std::endl; 16 | } 17 | } 18 | } 19 | 20 | } // namespace fpga_tools 21 | 22 | #endif //__EXCEPTIONHANDLER_HPP__ 23 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd_accelerated( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher/launch/accelerated_vadd_capture_agilex.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # 12 | # Licensed under the Apache License, Version 2.0 (the "License"); 13 | # you may not use this file except in compliance with the License. 14 | # You may obtain a copy of the License at 15 | # 16 | # http://www.apache.org/licenses/LICENSE-2.0 17 | # 18 | # Unless required by applicable law or agreed to in writing, software 19 | # distributed under the License is distributed on an "AS IS" BASIS, 20 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | # See the License for the specific language governing permissions and 22 | # limitations under the License. 23 | 24 | """Example launch file for a profiling analysis.""" 25 | 26 | from launch import LaunchDescription 27 | from launch_ros.actions import Node 28 | from tracetools_launch.action import Trace 29 | from tracetools_trace.tools.names import DEFAULT_CONTEXT 30 | from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS 31 | 32 | 33 | def generate_launch_description(): 34 | return LaunchDescription( 35 | [ 36 | Trace( 37 | session_name="accelerated_vadd_capture_agilex", 38 | events_ust=[ 39 | "ros2_acceleration:vadd_pre", 40 | "ros2_acceleration:vadd_post", 41 | ] 42 | + DEFAULT_EVENTS_ROS, 43 | events_kernel=[ 44 | "sched_switch", 45 | ], 46 | # context_names=[ 47 | # "ip", 48 | # ] 49 | # + DEFAULT_CONTEXT, 50 | ), 51 | Node( 52 | package="accelerated_vadd_publisher", 53 | executable="accelerated_vadd_publisher_agilex", 54 | # arguments=["do_more"], 55 | output="screen", 56 | ), 57 | ] 58 | ) 59 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | accelerated_vadd_publisher 5 | 0.1.0 6 | A trivial double vector-add ROS 2 publisher that adds two 7 | inputs to a vector in a loop and attempts to publish them on the go 8 | at 10 Hz. Vector add operations are offloaded into to the FPGA. 9 | 10 | Víctor Mayoral Vilches 11 | Apache License 2.0 12 | Víctor Mayoral Vilches 13 | 14 | ament_cmake 15 | ament_vitis 16 | ament_oneapi 17 | 18 | acceleration_firmware_agilex7 19 | accelerated_doublevadd_publisher 20 | 21 | rclcpp 22 | std_msgs 23 | tracetools 24 | ament_acceleration 25 | tracetools_acceleration 26 | 27 | 28 | rclcpp 29 | std_msgs 30 | ament_lint_auto 31 | ament_lint_common 32 | 33 | 34 | ament_cmake 35 | 36 | 37 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(accelerated_vadd_publisher_once) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(std_msgs REQUIRED) 16 | find_package(OpenCL REQUIRED) 17 | find_package(Threads REQUIRED) 18 | find_package(vitis_common REQUIRED) 19 | find_package(ament_vitis) 20 | 21 | # accelerated_vadd_publisher 22 | add_executable(accelerated_vadd_publisher_once 23 | src/accelerated_vadd_publisher_once.cpp 24 | # src/vadd.cpp 25 | ) 26 | target_include_directories(accelerated_vadd_publisher_once PUBLIC 27 | include 28 | # $ENV{XILINX_HLS}/common/technology/autopilot 29 | ) 30 | target_link_libraries(accelerated_vadd_publisher_once 31 | ${OpenCL_LIBRARY} 32 | pthread 33 | ) 34 | ament_target_dependencies(accelerated_vadd_publisher_once 35 | rclcpp 36 | std_msgs 37 | ) 38 | 39 | if(ROS_ACCELERATION) 40 | # Generate Tcl script for analysis 41 | vitis_hls_generate_tcl( 42 | PROJECT 43 | project_accelerated_vadd_publisher_once 44 | SRC 45 | src/vadd.cpp 46 | HEADERS 47 | include 48 | TESTBENCH 49 | src/testbench_vadd.cpp 50 | TOPFUNCTION 51 | vadd 52 | CLOCK 53 | 4 54 | SYNTHESIS 55 | ) 56 | 57 | # vadd kernel 58 | vitis_acceleration_kernel( 59 | NAME vadd 60 | FILE src/vadd.cpp 61 | CONFIG src/kv260.cfg 62 | INCLUDE 63 | include 64 | TYPE 65 | # sw_emu 66 | # hw_emu 67 | hw 68 | PACKAGE 69 | ) 70 | endif() 71 | 72 | install(TARGETS 73 | accelerated_vadd_publisher_once 74 | DESTINATION lib/${PROJECT_NAME} 75 | ) 76 | 77 | if(BUILD_TESTING) 78 | find_package(ament_lint_auto REQUIRED) 79 | ament_lint_auto_find_test_dependencies() 80 | endif() 81 | 82 | ament_package() 83 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/COLCON_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/accelerated_vadd_publisher_once/COLCON_IGNORE -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | accelerated_vadd_publisher_once 5 | 0.3.0 6 | A trivial vector-add ROS 2 publisher that adds two 7 | inputs to a vector and publishes only once. Vector add operations 8 | are offloaded into to the FPGA. 9 | 10 | This example is meant only for FPGA-evaluation purposes. See 11 | "accelerated_vadd_publisher" for a publisher that continuously publishes. 12 | 13 | The offloading operation into the FPGA (or to the Programmable Logic (PL)) 14 | allows the publisher to meet its targeted rate (10 Hz). See "vadd_publisher" 15 | for a version running purely on the CPUs which fails to maintain the publication 16 | rate. 17 | 18 | Víctor Mayoral Vilches 19 | Apache License 2.0 20 | Víctor Mayoral Vilches 21 | 22 | ament_cmake 23 | ament_vitis 24 | 25 | rclcpp 26 | std_msgs 27 | vitis_common 28 | 29 | 30 | rclcpp 31 | std_msgs 32 | acceleration_firmware_kv260 33 | 34 | ament_lint_auto 35 | ament_lint_common 36 | 37 | 38 | ament_cmake 39 | 40 | 41 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_ispMipiRx_vmixDP 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | # [clock] 10 | # defaultFreqHz=100000000 -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/accelerated_vadd_publisher_once/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | #ifndef DOUBLEVADD_COMPONENT_HPP_ 26 | #define DOUBLEVADD_COMPONENT_HPP_ 27 | 28 | #include "rclcpp/rclcpp.hpp" 29 | #include "std_msgs/msg/string.hpp" 30 | #include 31 | 32 | #define DATA_SIZE 4096 // 2**12 33 | // #define DATA_SIZE 16384 // 2**14 34 | // #define DATA_SIZE 65536 // 2**16 35 | // #define DATA_SIZE 262144 // 2**18 36 | 37 | namespace composition 38 | { 39 | 40 | class DoubleVaddComponent : public rclcpp::Node 41 | { 42 | public: 43 | explicit DoubleVaddComponent(const rclcpp::NodeOptions & options) 44 | : Node("doublevadd_publisher", options), count_(0) {initialize();} 45 | 46 | explicit DoubleVaddComponent(const std::string &node_name, 47 | const rclcpp::NodeOptions & options) 48 | : Node(node_name, options), count_(0) {initialize();} 49 | 50 | int publish_count_ = 0; 51 | 52 | protected: 53 | void on_timer(); 54 | 55 | private: 56 | void initialize(); 57 | 58 | rclcpp::Publisher::SharedPtr pub_; 59 | rclcpp::TimerBase::SharedPtr timer_; 60 | std::chrono::milliseconds dt_; 61 | 62 | unsigned int in1_[DATA_SIZE]; 63 | unsigned int in2_[DATA_SIZE]; 64 | unsigned int out_[DATA_SIZE]; 65 | 66 | size_t count_; 67 | 68 | }; 69 | 70 | } // namespace composition 71 | 72 | #endif // DOUBLEVADD_COMPONENT_HPP_ 73 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/include/doublevadd_component_adaptive.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | #ifndef DOUBLEVADD_COMPONENT_ADAPTIVE_HPP_ 26 | #define DOUBLEVADD_COMPONENT_ADAPTIVE_HPP_ 27 | 28 | #include "rclcpp/rclcpp.hpp" 29 | #include "doublevadd_component.hpp" 30 | #include "doublevadd_component_fpga.hpp" 31 | #include "adaptive_component/adaptive_component.hpp" 32 | 33 | namespace composition 34 | { 35 | 36 | /// An Adaptive Component built using using an adaptive_component ROS 2 package. 37 | /* 38 | * Publishes vadd operations while supporting different compute substrates (CPU, 39 | * FPGA), allowing for on-the-go changes following adaptive_component conventions. 40 | */ 41 | class DoubleVaddComponentAdaptive : public AdaptiveComponent 42 | { 43 | public: 44 | /// Default constructor 45 | explicit DoubleVaddComponentAdaptive(const rclcpp::NodeOptions & options); 46 | }; 47 | 48 | } // namespace composition 49 | 50 | #endif // DOUBLEVADD_COMPONENT_ADAPTIVE_HPP_ 51 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/include/doublevadd_component_adaptive_stateful.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | #ifndef DOUBLEVADD_COMPONENT_ADAPTIVE_STATEFUL_HPP_ 26 | #define DOUBLEVADD_COMPONENT_ADAPTIVE_STATEFUL_HPP_ 27 | 28 | #include "rclcpp/rclcpp.hpp" 29 | #include "doublevadd_component.hpp" 30 | #include "doublevadd_component_fpga.hpp" 31 | #include "adaptive_component/adaptive_component.hpp" 32 | 33 | namespace composition 34 | { 35 | 36 | /// An stateful Adaptive Component built using using an adaptive_component ROS 2 package. 37 | /* 38 | * Publishes vadd operations while supporting different compute substrates (CPU, 39 | * FPGA), allowing for on-the-go changes following adaptive_component conventions. 40 | */ 41 | class DoubleVaddComponentAdaptiveStateful : public AdaptiveComponent 42 | { 43 | public: 44 | /// Default constructor 45 | explicit DoubleVaddComponentAdaptiveStateful(const rclcpp::NodeOptions & options); 46 | 47 | protected: 48 | void on_timer(void); 49 | int count; 50 | 51 | }; 52 | 53 | } // namespace composition 54 | 55 | #endif // DOUBLEVADD_COMPONENT_ADAPTIVE_STATEFUL_HPP_ 56 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/launch/vadd_capture.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # 12 | # Licensed under the Apache License, Version 2.0 (the "License"); 13 | # you may not use this file except in compliance with the License. 14 | # You may obtain a copy of the License at 15 | # 16 | # http://www.apache.org/licenses/LICENSE-2.0 17 | # 18 | # Unless required by applicable law or agreed to in writing, software 19 | # distributed under the License is distributed on an "AS IS" BASIS, 20 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | # See the License for the specific language governing permissions and 22 | # limitations under the License. 23 | 24 | """Example launch file for a profiling analysis.""" 25 | 26 | from launch import LaunchDescription 27 | from launch_ros.actions import Node 28 | from tracetools_launch.action import Trace 29 | from tracetools_trace.tools.names import DEFAULT_CONTEXT 30 | from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS 31 | 32 | 33 | def generate_launch_description(): 34 | return LaunchDescription( 35 | [ 36 | Trace( 37 | session_name="vadd_capture", 38 | events_ust=[ 39 | "ros2_acceleration:vadd_pre", 40 | "ros2_acceleration:vadd_post", 41 | ] 42 | + DEFAULT_EVENTS_ROS, 43 | events_kernel=[ 44 | "sched_switch", 45 | ], 46 | # context_names=[ 47 | # "ip", 48 | # ] 49 | # + DEFAULT_CONTEXT, 50 | ), 51 | Node( 52 | package="doublevadd_publisher", 53 | executable="doublevadd_publisher", 54 | # arguments=["do_more"], 55 | output="screen", 56 | ), 57 | ] 58 | ) 59 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | doublevadd_publisher 5 | 0.3.0 6 | A trivial double vector-add ROS 2 publisher. 7 | Adds two inputs to a vector in a loop and publishes on the go at 8 | 10 Hz. Running in hardware shows that it's not 9 | able to meet the rate target and stays at around 2 Hz. 10 | 11 | The objective of this package is to generate a computationally expensive 12 | baseline when executed in a general purpose embedded CPU. See 13 | "accelerated_doublevadd_publisher" package for an optimized and accelerated version of the 14 | same package which offloads the vector operations into an FPGA. See 15 | "faster_doublevadd_publisher" for an even more optimized version. 16 | 17 | Víctor Mayoral Vilches 18 | Apache License 2.0 19 | Víctor Mayoral Vilches 20 | 21 | ament_cmake 22 | ament_vitis 23 | 24 | tracetools 25 | tracetools_acceleration 26 | adaptive_component 27 | vitis_common 28 | 29 | rclcpp 30 | std_msgs 31 | acceleration_firmware_kv260 32 | 33 | rclcpp 34 | std_msgs 35 | acceleration_firmware_kv260 36 | 37 | ament_lint_auto 38 | ament_lint_common 39 | 40 | 41 | ament_cmake 42 | 43 | 44 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/doublevadd_component_adaptive.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | An Adaptive Component built using using an adaptive_component ROS 2 package. 13 | 14 | Publishes vadd operations while supporting different compute substrates (CPU, 15 | FPGA), allowing for on-the-go changes following adaptive_component conventions. 16 | */ 17 | 18 | #include "rclcpp/rclcpp.hpp" 19 | #include "doublevadd_component.hpp" 20 | #include "doublevadd_component_fpga.hpp" 21 | #include "doublevadd_component_adaptive.hpp" 22 | 23 | using namespace std::chrono_literals; // NOLINT 24 | using NodeCPU = composition::DoubleVaddComponent; 25 | using NodeFPGA = composition::DoubleVaddComponentFPGA; 26 | 27 | namespace composition 28 | { 29 | DoubleVaddComponentAdaptive::DoubleVaddComponentAdaptive(const rclcpp::NodeOptions & options) 30 | : AdaptiveComponent("doublevadd_publisher_adaptive", // name of the adaptive Node 31 | options, // Node options 32 | // CPU 33 | std::make_shared("_doublevadd_publisher_adaptive_cpu", options), 34 | // FPGA 35 | std::make_shared("_doublevadd_publisher_adaptive_fpga", options), 36 | // GPU 37 | nullptr){} 38 | 39 | } // namespace composition 40 | 41 | #include "rclcpp_components/register_node_macro.hpp" 42 | RCLCPP_COMPONENTS_REGISTER_NODE(composition::DoubleVaddComponentAdaptive) 43 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/doublevadd_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // A publisher built using components 26 | 27 | #include 28 | #include "doublevadd_component.hpp" 29 | #include "rclcpp/rclcpp.hpp" 30 | 31 | int main(int argc, char * argv[]) 32 | { 33 | rclcpp::init(argc, argv); 34 | rclcpp::spin(std::make_shared(rclcpp::NodeOptions())); 35 | rclcpp::shutdown(); 36 | return 0; 37 | } 38 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/doublevadd_publisher_adaptive.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | An Adaptive Node built out of "Components". The Node defaults to 13 | CPU computations and can dynamically offload to the FPGA and adapt 14 | accordingly. 15 | 16 | The Node leverages the "AdaptiveComponent" class to simplify the creation of 17 | adaptive Node behaviors through parameters. 18 | */ 19 | 20 | #include "rclcpp/rclcpp.hpp" 21 | #include "doublevadd_component.hpp" 22 | #include "doublevadd_component_fpga.hpp" 23 | #include "adaptive_component/adaptive_component.hpp" 24 | 25 | int main(int argc, char * argv[]) 26 | { 27 | rclcpp::init(argc, argv); 28 | rclcpp::NodeOptions options; 29 | rclcpp::executors::MultiThreadedExecutor exec; 30 | using NodeCPU = composition::DoubleVaddComponent; 31 | using NodeFPGA = composition::DoubleVaddComponentFPGA; 32 | 33 | // Create an adaptive ROS 2 Node using "components", the resulting 34 | // Node is also programed as a "component", retaining composability 35 | auto adaptive_node = std::make_shared( 36 | "doublevadd_publisher_adaptive", // name of the adaptive Node 37 | options, // Node options 38 | // CPU 39 | std::make_shared("_doublevadd_publisher_adaptive_cpu", options), 40 | // FPGA 41 | std::make_shared("_doublevadd_publisher_adaptive_fpga", options), 42 | // GPU 43 | nullptr); 44 | 45 | // fill up the executor 46 | exec.add_node(adaptive_node); 47 | 48 | // // Another Node 49 | // auto doublevadd_node3 = std::make_shared("doublevadd_node3", options); 50 | // exec.add_node(doublevadd_node3); 51 | 52 | exec.spin(); // spin the executor 53 | rclcpp::shutdown(); 54 | return 0; 55 | } 56 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/doublevadd_publisher_adaptive_with_components.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | An Adaptive Node built out of "Components". The Node defaults to 13 | CPU computations and can dynamically offload to the FPGA and adapt 14 | accordingly. 15 | 16 | The Node leverages the "AdaptiveComponent" class to simplify the creation of 17 | adaptive Node behaviors through parameters. 18 | */ 19 | 20 | #include "rclcpp/rclcpp.hpp" 21 | #include "doublevadd_component_adaptive.hpp" 22 | 23 | int main(int argc, char * argv[]) 24 | { 25 | using AdaptiveNode = composition::DoubleVaddComponentAdaptive; 26 | 27 | rclcpp::init(argc, argv); 28 | rclcpp::NodeOptions options; 29 | rclcpp::executors::MultiThreadedExecutor exec; 30 | 31 | // Make an Adaptive Node out of an Adaptive Component 32 | auto adaptive_node_with_components = std::make_shared(options); 33 | exec.add_node(adaptive_node_with_components); 34 | 35 | exec.spin(); // spin the executor 36 | rclcpp::shutdown(); 37 | return 0; 38 | } 39 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/doublevadd_publisher_adaptive_with_components_and_state.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | An Adaptive Node built out of "Components". The Node defaults to 13 | CPU computations and can dynamically offload to the FPGA and adapt 14 | accordingly. 15 | 16 | The Node leverages the "AdaptiveComponent" class to simplify the creation of 17 | adaptive Node behaviors through parameters. 18 | */ 19 | 20 | #include "rclcpp/rclcpp.hpp" 21 | #include "doublevadd_component_adaptive_stateful.hpp" 22 | 23 | int main(int argc, char * argv[]) 24 | { 25 | using AdaptiveNode = composition::DoubleVaddComponentAdaptiveStateful; 26 | 27 | rclcpp::init(argc, argv); 28 | rclcpp::NodeOptions options; 29 | rclcpp::executors::MultiThreadedExecutor exec; 30 | 31 | // Make an Adaptive Node out of an Adaptive Component 32 | auto adaptive_node_with_components_and_state = std::make_shared(options); 33 | exec.add_node(adaptive_node_with_components_and_state); 34 | 35 | exec.spin(); // spin the executor 36 | rclcpp::shutdown(); 37 | return 0; 38 | } 39 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/testbench.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include // NOLINT 17 | #include 18 | #include 19 | #include 20 | 21 | #include "vadd.hpp" 22 | 23 | #define DATA_SIZE 4096 // 2**12 24 | // #define DATA_SIZE 16384 // 2**14 25 | // #define DATA_SIZE 65536 // 2**16 26 | // #define DATA_SIZE 262144 // 2**18 27 | 28 | // using namespace std::chrono_literals; // NOLINT 29 | 30 | bool check_vadd( 31 | const unsigned int *in1, // Read-Only Vector 1 32 | const unsigned int *in2, // Read-Only Vector 2 33 | const unsigned int *out // Read-Only Result 34 | ) { 35 | bool match = true; 36 | // no need to iterate twice through the loop, math's the same 37 | for (int i = 0 ; i < DATA_SIZE ; i++) { 38 | unsigned int expected = in1[i]+in2[i]; 39 | if (out[i] != expected) { 40 | // std::cout << "Error: Result mismatch" << std::endl; 41 | // std::cout << "i = " << i << " CPU result = " 42 | // << expected << " Device result = " << out[i] << std::endl; 43 | match = false; 44 | break; 45 | } 46 | } 47 | return match; 48 | } 49 | 50 | int main(int argc, char * argv[]) { 51 | 52 | // Application variables 53 | unsigned int in1[DATA_SIZE]; 54 | unsigned int in2[DATA_SIZE]; 55 | unsigned int out[DATA_SIZE]; 56 | 57 | // randomize the vectors used 58 | for (int i = 0 ; i < DATA_SIZE ; i++) { 59 | in1[i] = rand() % DATA_SIZE; // NOLINT 60 | in2[i] = rand() % DATA_SIZE; // NOLINT 61 | out[i] = 0; 62 | } 63 | 64 | // Add vectors 65 | vadd(in1, in2, out, DATA_SIZE); // function subject to be accelerated 66 | 67 | // Validate operation 68 | check_vadd(in1, in2, out); 69 | 70 | return 0; 71 | } 72 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | for (int j = 0; j < size; ++j) { // stupidly iterate over 30 | // it to generate load 31 | #pragma HLS loop_tripcount min = c_size max = c_size 32 | for (int i = 0; i < size; ++i) { 33 | #pragma HLS loop_tripcount min = c_size max = c_size 34 | out[i] = in1[i] + in2[i]; 35 | } 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /nodes/doublevadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/launch/vadd_capture.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # 12 | # Licensed under the Apache License, Version 2.0 (the "License"); 13 | # you may not use this file except in compliance with the License. 14 | # You may obtain a copy of the License at 15 | # 16 | # http://www.apache.org/licenses/LICENSE-2.0 17 | # 18 | # Unless required by applicable law or agreed to in writing, software 19 | # distributed under the License is distributed on an "AS IS" BASIS, 20 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | # See the License for the specific language governing permissions and 22 | # limitations under the License. 23 | 24 | """Example launch file for a profiling analysis.""" 25 | 26 | from launch import LaunchDescription 27 | from launch_ros.actions import Node 28 | from tracetools_launch.action import Trace 29 | from tracetools_trace.tools.names import DEFAULT_CONTEXT 30 | from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS 31 | 32 | 33 | def generate_launch_description(): 34 | return LaunchDescription( 35 | [ 36 | Trace( 37 | session_name="faster_doublevadd_publisher", 38 | events_ust=[ 39 | "ros2_acceleration:vadd_pre", 40 | "ros2_acceleration:vadd_post", 41 | ] 42 | + DEFAULT_EVENTS_ROS, 43 | events_kernel=[ 44 | "sched_switch", 45 | ], 46 | # context_names=[ 47 | # "ip", 48 | # ] 49 | # + DEFAULT_CONTEXT, 50 | ), 51 | Node( 52 | package="faster_doublevadd_publisher", 53 | executable="faster_doublevadd_publisher", 54 | # arguments=["do_more"], 55 | output="screen", 56 | ), 57 | ] 58 | ) 59 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | faster_doublevadd_publisher 5 | 0.3.0 6 | A trivial double vector-add ROS 2 publisher that adds two 7 | inputs to a vector in a loop and publishes them on the go at 10 Hz. 8 | Vector add operations are offloaded into to the FPGA and various HLS 9 | pragmas are used to demonstrate hardware acceleration. 10 | 11 | The acceleration operation into the FPGA (or to the Programmable Logic (PL)) 12 | allows the publisher to meet its targeted rate (10 Hz). See "doublevadd_publisher" 13 | for a version running purely on the CPUs which publishes at 2 Hz. See 14 | "accelerated_doublevadd_publisher" for another version which uses the HLS INTERFACE 15 | pragma to create two m_axi ports (instead of a single one, which is the 16 | default behavior with HLS) in the vadd kernel allowing to simultaneously 17 | perform reads and writes on the two vectors passed as arguments to the kernel. 18 | 19 | Víctor Mayoral Vilches 20 | Apache License 2.0 21 | Víctor Mayoral Vilches 22 | 23 | ament_cmake 24 | ament_vitis 25 | 26 | tracetools 27 | tracetools_acceleration 28 | 29 | rclcpp 30 | std_msgs 31 | vitis_common 32 | 33 | rclcpp 34 | std_msgs 35 | 36 | ament_lint_auto 37 | ament_lint_common 38 | 39 | 40 | ament_cmake 41 | 42 | 43 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | [clock] 10 | #freqHz=100000000:vadd_faster_1 11 | freqHz=80000000:vadd_faster_1 12 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/faster_doublevadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_faster( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/faster_triplevadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | faster_triplevadd_publisher 5 | 0.3.0 6 | A trivial triple vector-add ROS 2 publisher that adds two 7 | inputs to a vector in a loop and publishes them on the go at 10 Hz. 8 | Vector add operations are offloaded into to the FPGA and various HLS 9 | pragmas are used to demonstrate hardware acceleration. 10 | 11 | Víctor Mayoral Vilches 12 | Apache License 2.0 13 | Víctor Mayoral Vilches 14 | 15 | ament_cmake 16 | ament_vitis 17 | 18 | rclcpp 19 | std_msgs 20 | vitis_common 21 | 22 | rclcpp 23 | std_msgs 24 | 25 | ament_lint_auto 26 | ament_lint_common 27 | 28 | 29 | ament_cmake 30 | 31 | 32 | -------------------------------------------------------------------------------- /nodes/faster_triplevadd_publisher/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/faster_triplevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/faster_triplevadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/launch/rectify_resize.launch.py: -------------------------------------------------------------------------------- 1 | import os 2 | from launch import LaunchDescription 3 | from launch_ros.actions import Node 4 | from launch_ros.substitutions import FindPackageShare 5 | from launch_ros.actions import ComposableNodeContainer 6 | from launch_ros.descriptions import ComposableNode 7 | 8 | def generate_launch_description(): 9 | # Trace 10 | 11 | perception_container = ComposableNodeContainer( 12 | name="perception_container", 13 | namespace="", 14 | package="rclcpp_components", 15 | executable="component_container", 16 | composable_node_descriptions=[ 17 | ComposableNode( 18 | package="image_proc", 19 | plugin="image_proc::RectifyNode", 20 | name="rectify_node", 21 | remappings=[ 22 | ("image", "/camera/image_raw"), 23 | ("camera_info", "/camera/camera_info"), 24 | ], 25 | ), 26 | 27 | ComposableNode( 28 | namespace="resize", 29 | package="image_proc", 30 | plugin="image_proc::ResizeNode", 31 | name="resize_node", 32 | remappings=[ 33 | ("camera_info", "/camera/camera_info"), 34 | ("image", "/image_rect"), 35 | ("resize", "resize"), 36 | ], 37 | parameters=[ 38 | { 39 | "scale_height": 2.0, 40 | "scale_width": 2.0, 41 | } 42 | ], 43 | ), 44 | ], 45 | output="screen", 46 | ) 47 | 48 | return LaunchDescription([ 49 | # image pipeline 50 | perception_container 51 | ]) -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | image_pipeline_examples 5 | 0.3.0 6 | 7 | Provides Node wrappers to group together and demonstrate various 8 | combinations of hardware accelerated perception pipelines 9 | using the image_pipeline package. 10 | 11 | Víctor Mayoral Vilches 12 | Apache License 2.0 13 | Víctor Mayoral Vilches 14 | 15 | ament_cmake 16 | ament_vitis 17 | ament_cuda 18 | 19 | image_proc 20 | isaac_ros_image_proc 21 | rclcpp 22 | 23 | 24 | ament_lint_auto 25 | ament_lint_common 26 | 27 | 28 | ament_cmake 29 | 30 | 31 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify.hpp" 30 | #include "rclcpp/rclcpp.hpp" 31 | 32 | int main(int argc, char * argv[]) 33 | { 34 | rclcpp::init(argc, argv); 35 | rclcpp::spin( 36 | std::make_shared(rclcpp::NodeOptions())); 37 | rclcpp::shutdown(); 38 | return 0; 39 | } 40 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_fpga_integrated_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify_resize_fpga_integrated.hpp" 30 | #include "rclcpp/rclcpp.hpp" 31 | 32 | int main(int argc, char * argv[]) 33 | { 34 | rclcpp::init(argc, argv); 35 | rclcpp::spin( 36 | std::make_shared(rclcpp::NodeOptions())); 37 | rclcpp::shutdown(); 38 | return 0; 39 | } 40 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_fpga_integrated_streamlined_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify_resize_fpga_streamlined.hpp" 30 | // #include "image_proc/rectify_resize_fpga_streamlined_xrt.hpp" 31 | #include "rclcpp/rclcpp.hpp" 32 | 33 | int main(int argc, char * argv[]) 34 | { 35 | rclcpp::init(argc, argv); 36 | rclcpp::spin( 37 | std::make_shared(rclcpp::NodeOptions())); 38 | rclcpp::shutdown(); 39 | return 0; 40 | } 41 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_fpga_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify_fpga.hpp" 30 | #include "image_proc/resize_fpga.hpp" 31 | #include "rclcpp/rclcpp.hpp" 32 | 33 | int main(int argc, char * argv[]) 34 | { 35 | rclcpp::init(argc, argv); 36 | 37 | // rclcpp::executors::SingleThreadedExecutor exec; 38 | rclcpp::executors::MultiThreadedExecutor exec; 39 | rclcpp::NodeOptions options; 40 | auto rectify_node = 41 | std::make_shared(options); 42 | auto resize_node = 43 | std::make_shared(options); 44 | exec.add_node(rectify_node); 45 | exec.add_node(resize_node); 46 | 47 | exec.spin(); 48 | rclcpp::shutdown(); 49 | return 0; 50 | } 51 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_fpga_streamlined_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify_fpga_streamlined.hpp" 30 | #include "image_proc/resize_fpga_streamlined.hpp" 31 | #include "rclcpp/rclcpp.hpp" 32 | 33 | int main(int argc, char * argv[]) 34 | { 35 | rclcpp::init(argc, argv); 36 | 37 | // rclcpp::executors::SingleThreadedExecutor exec; 38 | rclcpp::executors::MultiThreadedExecutor exec; 39 | rclcpp::NodeOptions options; 40 | auto rectify_node = 41 | std::make_shared(options); 42 | auto resize_node = 43 | std::make_shared(options); 44 | exec.add_node(rectify_node); 45 | exec.add_node(resize_node); 46 | 47 | exec.spin(); 48 | rclcpp::shutdown(); 49 | return 0; 50 | } 51 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_fpga_streamlined_node_xrt.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify_fpga_streamlined_xrt.hpp" 30 | #include "image_proc/resize_fpga_streamlined_xrt.hpp" 31 | // #include "image_proc/resize_fpga_streamlined.hpp" 32 | #include "rclcpp/rclcpp.hpp" 33 | 34 | int main(int argc, char * argv[]) 35 | { 36 | rclcpp::init(argc, argv); 37 | 38 | // rclcpp::executors::SingleThreadedExecutor exec; 39 | rclcpp::executors::MultiThreadedExecutor exec; 40 | rclcpp::NodeOptions options; 41 | auto resize_node = 42 | std::make_shared(options); 43 | auto rectify_node = 44 | std::make_shared(options); 45 | 46 | exec.add_node(rectify_node); 47 | exec.add_node(resize_node); 48 | 49 | exec.spin(); 50 | rclcpp::shutdown(); 51 | return 0; 52 | } 53 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_gpu_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "isaac_ros_image_proc/rectify_node.hpp" 30 | #include "isaac_ros_image_proc/resize_node.hpp" 31 | #include "rclcpp/rclcpp.hpp" 32 | 33 | int main(int argc, char * argv[]) 34 | { 35 | rclcpp::init(argc, argv); 36 | 37 | rclcpp::executors::SingleThreadedExecutor exec; 38 | // rclcpp::executors::MultiThreadedExecutor exec; 39 | rclcpp::NodeOptions options; 40 | // auto rectify_node = 41 | // std::make_shared(options); 42 | // auto resize_node = 43 | // std::make_shared(options); 44 | 45 | auto rectify_node = 46 | std::make_shared(options); 47 | auto resize_node = 48 | std::make_shared(options); 49 | exec.add_node(rectify_node); 50 | exec.add_node(resize_node); 51 | 52 | exec.spin(); 53 | rclcpp::shutdown(); 54 | return 0; 55 | } 56 | -------------------------------------------------------------------------------- /nodes/image_pipeline_examples/src/rectify_resize_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | // An image_pipeline rectify component into a node for tracing purposes. 26 | // see https://gitlab.com/ros-tracing/ros2_tracing/-/issues/137 27 | 28 | #include 29 | #include "image_proc/rectify.hpp" 30 | #include "image_proc/resize.hpp" 31 | #include "rclcpp/rclcpp.hpp" 32 | 33 | int main(int argc, char * argv[]) 34 | { 35 | rclcpp::init(argc, argv); 36 | 37 | rclcpp::executors::SingleThreadedExecutor exec; 38 | // rclcpp::executors::MultiThreadedExecutor exec; 39 | rclcpp::NodeOptions options; 40 | auto rectify_node = 41 | std::make_shared(options); 42 | auto resize_node = 43 | std::make_shared(options); 44 | 45 | exec.add_node(rectify_node); 46 | exec.add_node(resize_node); 47 | 48 | exec.spin(); 49 | rclcpp::shutdown(); 50 | return 0; 51 | } 52 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/include/image_proc_adaptive.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | */ 24 | 25 | #ifndef IMAGE_PROC_ADAPTIVE_HPP_ 26 | #define IMAGE_PROC_ADAPTIVE_HPP_ 27 | 28 | #include "rclcpp/rclcpp.hpp" 29 | #include "adaptive_component/adaptive_component.hpp" 30 | 31 | namespace composition 32 | { 33 | 34 | class ResizeNodeAdaptive : public AdaptiveComponent 35 | { 36 | public: 37 | /// Default constructor 38 | explicit ResizeNodeAdaptive(const rclcpp::NodeOptions & options); 39 | }; 40 | 41 | } // namespace composition 42 | 43 | #endif // IMAGE_PROC_ADAPTIVE_HPP_ 44 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/launch/image_proc_adaptive.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # Licensed under the Apache License, Version 2.0 12 | # 13 | 14 | 15 | from launch import LaunchDescription 16 | from launch_ros.actions import ComposableNodeContainer 17 | from launch_ros.descriptions import ComposableNode 18 | from launch_ros.actions import Node 19 | 20 | 21 | def generate_launch_description(): 22 | 23 | container = ComposableNodeContainer( 24 | name="resize_container", 25 | namespace="", 26 | package="rclcpp_components", 27 | executable="component_container", 28 | composable_node_descriptions=[ 29 | # TODO: consider subclassing ComposableNode and creating an 30 | # AdaptiveNode class that allows for launch-time remapping of 31 | # names, topics, etc. 32 | ComposableNode( 33 | package="image_proc_adaptive", 34 | plugin="composition::ResizeNodeAdaptive", 35 | name="ResizeNode_adaptive", 36 | ), 37 | # ComposableNode( 38 | # package="image_proc", 39 | # plugin="image_proc::ResizeNode", 40 | # name="resize_node", 41 | # ), 42 | # ComposableNode( 43 | # package="image_proc", 44 | # plugin="image_proc::ResizeNodeFPGA", 45 | # name="resize_fpga_node", 46 | # ), 47 | ], 48 | output="screen", 49 | ) 50 | 51 | return LaunchDescription([container]) 52 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | image_proc_adaptive 5 | 0.3.0 6 | 7 | An example that makes use of the image_pipeline meta-package to demonstrate 8 | how to make a ROS 2 image_proc adaptive Component that can run either 9 | in CPU or in the FPGA. 10 | 11 | Víctor Mayoral Vilches 12 | Apache License 2.0 13 | Víctor Mayoral Vilches 14 | 15 | ament_cmake 16 | ament_vitis 17 | 18 | 20 | adaptive_component 21 | rclcpp 22 | image_proc 23 | opencl-headers 24 | ocl-icd-dev 25 | ocl-icd-libopencl1 26 | ocl-icd-opencl-dev 27 | 28 | ament_lint_auto 29 | ament_lint_common 30 | 31 | 32 | ament_cmake 33 | 34 | 35 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/src/image_proc_adaptive.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | 24 | 25 | An image_proc adaptive ROS 2 Component. 26 | 27 | Supports CPU or FPGA computations, allows for on-the-go changes following 28 | adaptive_component conventions (see https://github.com/ros-acceleration/adaptive_component). 29 | */ 30 | 31 | #include "rclcpp/rclcpp.hpp" 32 | #include "image_proc/resize.hpp" 33 | #include "image_proc/resize_fpga.hpp" 34 | #include "image_proc_adaptive.hpp" 35 | 36 | using namespace std::chrono_literals; // NOLINT 37 | using NodeCPU = image_proc::ResizeNode; 38 | using NodeFPGA = image_proc::ResizeNodeFPGA; 39 | 40 | namespace composition 41 | { 42 | ResizeNodeAdaptive::ResizeNodeAdaptive(const rclcpp::NodeOptions & options) 43 | : AdaptiveComponent("ResizeNode_adaptive", // name of the adaptive Node 44 | options, // Node options 45 | // CPU 46 | std::make_shared(options), 47 | // FPGA 48 | std::make_shared(options), 49 | // GPU 50 | nullptr){} 51 | 52 | } // namespace composition 53 | 54 | #include "rclcpp_components/register_node_macro.hpp" 55 | RCLCPP_COMPONENTS_REGISTER_NODE(composition::ResizeNodeAdaptive) 56 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/src/image_proc_node_adaptive.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Licensed under the Apache License, Version 2.0 (the "License"); 13 | you may not use this file except in compliance with the License. 14 | You may obtain a copy of the License at 15 | 16 | http://www.apache.org/licenses/LICENSE-2.0 17 | 18 | Unless required by applicable law or agreed to in writing, software 19 | distributed under the License is distributed on an "AS IS" BASIS, 20 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | See the License for the specific language governing permissions and 22 | limitations under the License. 23 | 24 | 25 | An image_proc adaptive ROS 2 Node using Components. 26 | 27 | Supports CPU or FPGA computations, allows for on-the-go changes following 28 | adaptive_component conventions (see https://github.com/ros-acceleration/adaptive_component). 29 | */ 30 | 31 | #include "rclcpp/rclcpp.hpp" 32 | #include "image_proc_adaptive.hpp" 33 | 34 | int main(int argc, char * argv[]) 35 | { 36 | using AdaptiveNode = composition::ResizeNodeAdaptive; 37 | 38 | rclcpp::init(argc, argv); 39 | rclcpp::NodeOptions options; 40 | rclcpp::executors::MultiThreadedExecutor exec; 41 | 42 | // Make an Adaptive Node out of an Adaptive Component 43 | auto adaptive_node_with_components_and_state = std::make_shared(options); 44 | exec.add_node(adaptive_node_with_components_and_state); 45 | 46 | exec.spin(); // spin the executor 47 | rclcpp::shutdown(); 48 | return 0; 49 | } 50 | -------------------------------------------------------------------------------- /nodes/image_proc_adaptive/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | multiple_doublevadd_publisher 5 | 0.3.0 6 | This package presents multiple double vector-add ROS 2 publishers 7 | that adds two inputs to a vector in a loop and attempt publish them on the go 8 | at 10 Hz. Vector add operations are offloaded into to the FPGA and various HLS 9 | pragmas are used to demonstrate hardware acceleration. 10 | 11 | The package smashes various acceleration kernels into a single bitstream that 12 | can then be used to program the FPGA, allowing to run various kernels without 13 | reprogramming it. 14 | 15 | Víctor Mayoral Vilches 16 | Apache License 2.0 17 | Víctor Mayoral Vilches 18 | 19 | ament_cmake 20 | ament_vitis 21 | 22 | tracetools 23 | tracetools_acceleration 24 | 25 | rclcpp 26 | std_msgs 27 | vitis_common 28 | 29 | rclcpp 30 | std_msgs 31 | 32 | ament_lint_auto 33 | ament_lint_common 34 | 35 | 36 | ament_cmake 37 | 38 | 39 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/src/kv260_multiple.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | [clock] 10 | freqHz=100000000:vadd_faster_1 11 | freqHz=100000000:vadd_accelerated_1 12 | freqHz=100000000:vadd_offloaded_1 13 | 14 | [connectivity] 15 | sp=vadd_faster_1.in1:HP0 16 | sp=vadd_faster_1.in2:HP0 17 | sp=vadd_accelerated_1.in1:HP3 18 | sp=vadd_accelerated_1.in2:HP3 19 | sp=vadd_offloaded_1.in1:HP2 20 | sp=vadd_offloaded_1.in2:HP2 21 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/src/vadd_accelerated.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_accelerated( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j < size; ++j) { // stupidly iterate over 34 | // it to generate load 35 | #pragma HLS loop_tripcount min = c_size max = c_size 36 | for (int i = 0; i < size; ++i) { 37 | #pragma HLS loop_tripcount min = c_size max = c_size 38 | out[i] = in1[i] + in2[i]; 39 | } 40 | } 41 | } 42 | } 43 | -------------------------------------------------------------------------------- /nodes/multiple_doublevadd_publisher/src/vadd_faster.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_faster( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | #pragma HLS INTERFACE m_axi port=in1 bundle=aximm1 30 | #pragma HLS INTERFACE m_axi port=in2 bundle=aximm2 31 | #pragma HLS INTERFACE m_axi port=out bundle=aximm1 32 | 33 | for (int j = 0; j 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_offloaded( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | for (int j = 0; j < size; ++j) { // stupidly iterate over 30 | // it to generate load 31 | #pragma HLS loop_tripcount min = c_size max = c_size 32 | for (int i = 0; i < size; ++i) { 33 | #pragma HLS loop_tripcount min = c_size max = c_size 34 | out[i] = in1[i] + in2[i]; 35 | } 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(offloaded_doublevadd_publisher) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(std_msgs REQUIRED) 16 | find_package(Threads REQUIRED) 17 | find_package(ament_vitis) 18 | 19 | if (ROS_VITIS) 20 | find_package(vitis_common REQUIRED) 21 | find_package(OpenCL REQUIRED) 22 | 23 | # offloaded_doublevadd_publisher 24 | add_executable(offloaded_doublevadd_publisher 25 | src/offloaded_doublevadd_publisher.cpp 26 | src/vadd.cpp 27 | ) 28 | target_include_directories(offloaded_doublevadd_publisher PUBLIC include) 29 | target_link_libraries(offloaded_doublevadd_publisher 30 | ${OpenCL_LIBRARY} 31 | pthread 32 | ) 33 | ament_target_dependencies(offloaded_doublevadd_publisher 34 | rclcpp 35 | std_msgs 36 | vitis_common 37 | ) 38 | 39 | if(ROS_ACCELERATION) 40 | # C simulation and synthesis 41 | vitis_hls_generate_tcl( 42 | PROJECT 43 | project_offloaded_doublevadd_publisher 44 | SRC 45 | src/vadd.cpp 46 | HEADERS 47 | include 48 | TESTBENCH 49 | src/testbench.cpp 50 | TOPFUNCTION 51 | vadd_offloaded 52 | CLOCK 53 | 4 54 | SYNTHESIS 55 | ) 56 | 57 | 58 | # vadd kernel 59 | vitis_acceleration_kernel( 60 | NAME vadd_offloaded 61 | FILE src/vadd.cpp 62 | CONFIG src/kv260.cfg 63 | INCLUDE 64 | include 65 | TYPE 66 | # sw_emu 67 | # hw_emu 68 | hw 69 | LINK 70 | PACKAGE 71 | ) 72 | endif() 73 | 74 | install(TARGETS 75 | offloaded_doublevadd_publisher 76 | DESTINATION lib/${PROJECT_NAME} 77 | ) 78 | 79 | if(BUILD_TESTING) 80 | find_package(ament_lint_auto REQUIRED) 81 | ament_lint_auto_find_test_dependencies() 82 | endif() 83 | endif() # ROS_VITIS 84 | 85 | ament_package() 86 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd_offloaded( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/src/testbench.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include // NOLINT 17 | #include 18 | #include 19 | #include 20 | 21 | #include "vadd.hpp" 22 | 23 | #define DATA_SIZE 4096 // 2**12 24 | // #define DATA_SIZE 16384 // 2**14 25 | // #define DATA_SIZE 65536 // 2**16 26 | // #define DATA_SIZE 262144 // 2**18 27 | 28 | // using namespace std::chrono_literals; // NOLINT 29 | 30 | bool check_vadd( 31 | const unsigned int *in1, // Read-Only Vector 1 32 | const unsigned int *in2, // Read-Only Vector 2 33 | const unsigned int *out // Read-Only Result 34 | ) { 35 | bool match = true; 36 | // no need to iterate twice through the loop, math's the same 37 | for (int i = 0 ; i < DATA_SIZE ; i++) { 38 | unsigned int expected = in1[i]+in2[i]; 39 | if (out[i] != expected) { 40 | // std::cout << "Error: Result mismatch" << std::endl; 41 | // std::cout << "i = " << i << " CPU result = " 42 | // << expected << " Device result = " << out[i] << std::endl; 43 | match = false; 44 | break; 45 | } 46 | } 47 | return match; 48 | } 49 | 50 | int main(int argc, char * argv[]) { 51 | 52 | // Application variables 53 | unsigned int in1[DATA_SIZE]; 54 | unsigned int in2[DATA_SIZE]; 55 | unsigned int out[DATA_SIZE]; 56 | 57 | // randomize the vectors used 58 | for (int i = 0 ; i < DATA_SIZE ; i++) { 59 | in1[i] = rand() % DATA_SIZE; // NOLINT 60 | in2[i] = rand() % DATA_SIZE; // NOLINT 61 | out[i] = 0; 62 | } 63 | 64 | // Add vectors 65 | vadd_offloaded(in1, in2, out, DATA_SIZE); // function subject to be accelerated 66 | 67 | // Validate operation 68 | check_vadd(in1, in2, out); 69 | 70 | return 0; 71 | } 72 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd_offloaded( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | for (int j = 0; j < size; ++j) { // stupidly iterate over 30 | // it to generate load 31 | #pragma HLS loop_tripcount min = c_size max = c_size 32 | for (int i = 0; i < size; ++i) { 33 | #pragma HLS loop_tripcount min = c_size max = c_size 34 | out[i] = in1[i] + in2[i]; 35 | } 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /nodes/offloaded_doublevadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/publisher_xilinx/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(publisher_xilinx) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(std_msgs REQUIRED) 16 | 17 | # LTTng flame chart and graphs 18 | # see https://archive.eclipse.org/tracecompass/doc/stable/org.eclipse.tracecompass.doc.user/LTTng-UST-Analyses.html#Flame_Chart_View 19 | set(CMAKE_CXX_FLAGS "-g -O2 -finstrument-functions") 20 | 21 | add_executable(member_function_publisher member_function_publisher.cpp) 22 | ament_target_dependencies(member_function_publisher rclcpp std_msgs) 23 | 24 | install(TARGETS 25 | member_function_publisher 26 | DESTINATION lib/${PROJECT_NAME} 27 | ) 28 | 29 | if(BUILD_TESTING) 30 | find_package(ament_lint_auto REQUIRED) 31 | ament_lint_auto_find_test_dependencies() 32 | endif() 33 | 34 | # Install launch files 35 | install(DIRECTORY 36 | launch 37 | DESTINATION share/${PROJECT_NAME} 38 | ) 39 | 40 | ament_package() 41 | -------------------------------------------------------------------------------- /nodes/publisher_xilinx/launch/trace.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # Licensed under the Apache License, Version 2.0 (the "License"); 12 | # you may not use this file except in compliance with the License. 13 | # You may obtain a copy of the License at 14 | # 15 | # http://www.apache.org/licenses/LICENSE-2.0 16 | # 17 | # Unless required by applicable law or agreed to in writing, software 18 | # distributed under the License is distributed on an "AS IS" BASIS, 19 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 20 | # See the License for the specific language governing permissions and 21 | # limitations under the License. 22 | 23 | import os 24 | from launch import LaunchDescription 25 | from launch_ros.actions import Node 26 | from tracetools_launch.action import Trace 27 | from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS 28 | from tracetools_trace.tools.names import DEFAULT_EVENTS_KERNEL 29 | from tracetools_trace.tools.names import DEFAULT_CONTEXT 30 | 31 | def generate_launch_description(): 32 | # Trace 33 | trace = Trace( 34 | session_name="trace_publisher_xilinx", 35 | events_ust=[ 36 | "ros2_image_pipeline:*", 37 | "lttng_ust_cyg_profile*", 38 | "lttng_ust_statedump*", 39 | ] 40 | + DEFAULT_EVENTS_ROS, 41 | context_fields={ 42 | 'kernel': [], 43 | 'userspace': ['vpid', 'vtid', 'procname'], 44 | }, 45 | events_kernel=DEFAULT_EVENTS_KERNEL, 46 | # context_names=DEFAULT_CONTEXT, 47 | ) 48 | 49 | # An image_raw publisher 50 | publisher_xilinx = Node( 51 | package="publisher_xilinx", 52 | executable="member_function_publisher", 53 | name="publisher_xilinx", 54 | ) 55 | 56 | return LaunchDescription([ 57 | trace, 58 | publisher_xilinx 59 | ]) 60 | -------------------------------------------------------------------------------- /nodes/publisher_xilinx/member_function_publisher.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | */ 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #include "rclcpp/rclcpp.hpp" 20 | #include "std_msgs/msg/string.hpp" 21 | 22 | using namespace std::chrono_literals; 23 | 24 | /* This example creates a subclass of Node and uses std::bind() to register a 25 | * member function as a callback from the timer. */ 26 | 27 | class MinimalPublisher : public rclcpp::Node 28 | { 29 | public: 30 | MinimalPublisher() 31 | : Node("minimal_publisher"), count_(0) 32 | { 33 | publisher_ = this->create_publisher("topic", 10); 34 | timer_ = this->create_wall_timer( 35 | 500ms, std::bind(&MinimalPublisher::timer_callback, this)); 36 | } 37 | 38 | private: 39 | void timer_callback() 40 | { 41 | auto message = std_msgs::msg::String(); 42 | message.data = "Hello, Xilinx! " + std::to_string(count_++); 43 | RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str()); 44 | publisher_->publish(message); 45 | } 46 | rclcpp::TimerBase::SharedPtr timer_; 47 | rclcpp::Publisher::SharedPtr publisher_; 48 | size_t count_; 49 | }; 50 | 51 | int main(int argc, char * argv[]) 52 | { 53 | rclcpp::init(argc, argv); 54 | rclcpp::spin(std::make_shared()); 55 | rclcpp::shutdown(); 56 | return 0; 57 | } 58 | -------------------------------------------------------------------------------- /nodes/publisher_xilinx/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | publisher_xilinx 5 | 0.3.0 6 | A minimalistic publisher using a member function for evaluation purposes. 7 | Víctor Mayoral Vilches 8 | Apache License 2.0 9 | Víctor Mayoral Vilches 10 | 11 | ament_cmake 12 | 13 | rclcpp 14 | std_msgs 15 | 16 | rclcpp 17 | std_msgs 18 | 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | ament_cmake 24 | 25 | 26 | -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/1.png -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/2.png -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/3.png -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/4.png -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/5.png -------------------------------------------------------------------------------- /nodes/simple_adder/imgs/6.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/simple_adder/imgs/6.png -------------------------------------------------------------------------------- /nodes/simple_adder/include/adder.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | */ 13 | 14 | #ifndef XILINX_XILINX_EXAMPLES_SIMPLE_ADDER_INCLUDE_ADDER_HPP_ 15 | #define XILINX_XILINX_EXAMPLES_SIMPLE_ADDER_INCLUDE_ADDER_HPP_ 16 | 17 | extern "C" { 18 | int simple_adder(int a, int b); 19 | } // extern "C" 20 | 21 | #endif // XILINX_XILINX_EXAMPLES_SIMPLE_ADDER_INCLUDE_ADDER_HPP_ 22 | -------------------------------------------------------------------------------- /nodes/simple_adder/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | simple_adder 5 | 0.3.0 6 | A trivial adder example. 7 | Meant to demonstrate how HLS is integrated into build ROS 2 flows. 8 | 9 | No interactions with the ROS computational graph. 10 | 11 | Víctor Mayoral Vilches 12 | Apache License 2.0 13 | Víctor Mayoral Vilches 14 | 15 | ament_cmake 16 | ament_vitis 17 | 18 | acceleration_firmware_kv260 19 | ament_lint_auto 20 | ament_lint_common 21 | 22 | 23 | ament_cmake 24 | 25 | 26 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/adder1.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | extern "C" { 18 | int simple_adder(int a, int b) { 19 | int c; 20 | c = a + b; 21 | return c; 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/adder2.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | extern "C" { 18 | int simple_adder(int a, int b) { 19 | int c; 20 | c = a*a*a + b*b; 21 | return c; 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/testbench1.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include 17 | #include "adder.hpp" 18 | 19 | int main(void) { 20 | // Setup some required variables 21 | int a, b; 22 | int result, expected_result, error_count = 0; 23 | 24 | // Test Loop 25 | for (int i=0 ; i < 10 ; i++) { 26 | // Setup inputs 27 | a = i; 28 | b = 100+(2*i); 29 | // Predict result 30 | expected_result = a+b; 31 | // Call DUT 32 | result = simple_adder(a, b); 33 | // Check result and output some visual check 34 | if (result != expected_result) { 35 | error_count++; 36 | } 37 | printf("Expected result: %d, Got Result: %d\n", expected_result, result); 38 | } 39 | return error_count; 40 | } 41 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/testbench2.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include 17 | #include "adder.hpp" 18 | 19 | int main(void) { 20 | // Setup some required variables 21 | int a, b; 22 | int result, expected_result, error_count = 0; 23 | 24 | // Test Loop 25 | for (int i=0 ; i < 10 ; i++) { 26 | // Setup inputs 27 | a = i; 28 | b = 100+(2*i); 29 | // Predict result 30 | expected_result = a*a*a + b*b; 31 | // Call DUT 32 | result = simple_adder(a, b); 33 | // Check result and output some visual check 34 | if (result != expected_result) { 35 | error_count++; 36 | } 37 | printf("Expected result: %d, Got Result: %d\n", expected_result, result); 38 | } 39 | return error_count; 40 | } 41 | -------------------------------------------------------------------------------- /nodes/simple_adder/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/simple_vadd/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(simple_vadd) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(Threads REQUIRED) 15 | find_package(ament_vitis) 16 | 17 | if (ROS_VITIS) 18 | find_package(OpenCL REQUIRED) 19 | # find_package(vitis_common REQUIRED) 20 | 21 | # simple_vadd 22 | add_executable(simple_vadd 23 | src/vadd.cpp 24 | ) 25 | target_include_directories(simple_vadd PUBLIC include) 26 | target_link_libraries(simple_vadd 27 | ${OpenCL_LIBRARY} 28 | pthread 29 | ) 30 | # ament_target_dependencies(simple_vadd 31 | # vitis_common 32 | # ) 33 | 34 | # vadd kernel 35 | vitis_acceleration_kernel( 36 | NAME krnl_vadd 37 | FILE src/krnl_vadd.cpp 38 | CONFIG src/kv260.cfg 39 | # CLOCK 100000000:vadd 40 | INCLUDE 41 | include 42 | TYPE 43 | # sw_emu 44 | # hw_emu 45 | hw 46 | LINK 47 | PACKAGE 48 | ) 49 | 50 | install(TARGETS 51 | simple_vadd 52 | DESTINATION lib/${PROJECT_NAME} 53 | ) 54 | endif() # ROS_VITIS 55 | 56 | 57 | ament_package() 58 | -------------------------------------------------------------------------------- /nodes/simple_vadd/README.md: -------------------------------------------------------------------------------- 1 | # Vector Addition 2 | 3 | (*inspired by https://github.com/Xilinx/Vitis_Accel_Examples/tree/master/cpp_kernels/simple_vadd*) 4 | 5 | This is a simple example of vector addition. The kernel uses HLS Dataflow which allows the user to schedule multiple task together to achieve higher throughput. 6 | 7 | Vitis kernel can have one s_axilite interface which will be used by host application to configure the kernel. All the global memory access arguments are associated to m_axi(AXI Master Interface) as below: 8 | 9 | ```cpp 10 | 11 | #pragma HLS INTERFACE m_axi port = in1 bundle = gmem0 12 | #pragma HLS INTERFACE m_axi port = in2 bundle = gmem1 13 | #pragma HLS INTERFACE m_axi port = out bundle = gmem0 14 | ``` 15 | 16 | Multiple interfaces can be created based on the requirements. For example when multiple memory accessing arguments need access to global memory simultaneously, user can create multiple master interfaces and can connect to different arguments. 17 | 18 | Usually data stored in the array is consumed or produced in a sequential manner, a more efficient communication mechanism is to use streaming data as specified by the STREAM pragma, where FIFOs are used instead of RAMs. 19 | 20 | Vector addition in kernel is divided into 4 sub-tasks(read input 1, read input 2 , compute_add and write) which are then performed concurrently using ``Dataflow``. 21 | 22 | ```cpp 23 | 24 | #pragma HLS dataflow 25 | load_input(in1, in1_stream, size); 26 | load_input(in2, in2_stream, size); 27 | compute_add(in1_stream, in2_stream, out_stream, size); 28 | store_result(out, out_stream, size); 29 | ``` -------------------------------------------------------------------------------- /nodes/simple_vadd/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | simple_vadd 5 | 0.3.0 6 | A (NO ROS USED) simple example of vector addition that serves 7 | for validation purposes. 8 | 9 | Víctor Mayoral Vilches 10 | Apache License 2.0 11 | Víctor Mayoral Vilches 12 | 13 | ament_cmake 14 | ament_vitis 15 | 16 | acceleration_firmware_kv260 17 | 18 | 19 | 20 | ament_lint_auto 21 | ament_lint_common 22 | 23 | 24 | ament_cmake 25 | 26 | 27 | -------------------------------------------------------------------------------- /nodes/simple_vadd/src/kv260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | # [hls] 10 | # clock=300000000:vadd_accelerated 11 | -------------------------------------------------------------------------------- /nodes/simple_vadd/src/vadd.h: -------------------------------------------------------------------------------- 1 | /** 2 | * Copyright (C) 2019-2021 Xilinx, Inc 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"). You may 5 | * not use this file except in compliance with the License. A copy of the 6 | * License is located at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT 12 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the 13 | * License for the specific language governing permissions and limitations 14 | * under the License. 15 | */ 16 | #pragma once 17 | 18 | #define CL_HPP_CL_1_2_DEFAULT_BUILD 19 | #define CL_HPP_TARGET_OPENCL_VERSION 120 20 | #define CL_HPP_MINIMUM_OPENCL_VERSION 120 21 | #define CL_HPP_ENABLE_PROGRAM_CONSTRUCTION_FROM_ARRAY_COMPATIBILITY 1 22 | 23 | #include 24 | 25 | // Customized buffer allocation for 4K boundary alignment 26 | template 27 | struct aligned_allocator { 28 | using value_type = T; 29 | T* allocate(std::size_t num) { 30 | void* ptr = nullptr; 31 | if (posix_memalign(&ptr, 4096, num * sizeof(T))) throw std::bad_alloc(); 32 | return reinterpret_cast(ptr); 33 | } 34 | void deallocate(T* p, std::size_t num) { free(p); } 35 | }; 36 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(triplevadd_publisher) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(std_msgs REQUIRED) 16 | find_package(ament_vitis) 17 | 18 | add_executable(triplevadd_publisher src/triplevadd_publisher.cpp src/vadd.cpp) 19 | target_include_directories(triplevadd_publisher PUBLIC include) 20 | ament_target_dependencies(triplevadd_publisher rclcpp std_msgs) 21 | 22 | if(ROS_ACCELERATION) 23 | # C simulation and synthesis 24 | vitis_hls_generate_tcl( 25 | PROJECT 26 | project_triplevadd_publisher 27 | SRC 28 | src/vadd.cpp 29 | HEADERS 30 | include 31 | TESTBENCH 32 | src/testbench.cpp 33 | TOPFUNCTION 34 | vadd 35 | CLOCK 36 | 4 37 | SYNTHESIS 38 | ) 39 | endif() 40 | 41 | install(TARGETS 42 | triplevadd_publisher 43 | DESTINATION lib/${PROJECT_NAME} 44 | ) 45 | 46 | if(BUILD_TESTING) 47 | find_package(ament_lint_auto REQUIRED) 48 | ament_lint_auto_find_test_dependencies() 49 | endif() 50 | 51 | ament_package() 52 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/COLCON_IGNORE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/nodes/triplevadd_publisher/COLCON_IGNORE -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | triplevadd_publisher 5 | 0.3.0 6 | A a trivial triple vector-add ROS 2 publisher. 7 | Adds two inputs to a vector in a loop and publishes on the go at 8 | 10 Hz. 9 | 10 | The objective of this package is to generate a computationally expensive 11 | baseline when executed in a general purpose embedded CPU. See 12 | "accelerated_doublevadd_publisher" package for an optimized and accelerated version of the 13 | same package which offloads the vector operations into an FPGA. See 14 | "faster_doublevadd_publisher" for an even more optimized version. 15 | 16 | Víctor Mayoral Vilches 17 | Apache License 2.0 18 | Víctor Mayoral Vilches 19 | 20 | ament_cmake 21 | ament_vitis 22 | 23 | rclcpp 24 | std_msgs 25 | acceleration_firmware_kv260 26 | 27 | rclcpp 28 | std_msgs 29 | acceleration_firmware_kv260 30 | 31 | ament_lint_auto 32 | ament_lint_common 33 | 34 | 35 | ament_cmake 36 | 37 | 38 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/src/testbench.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include // NOLINT 17 | #include 18 | #include 19 | #include 20 | 21 | #include "vadd.hpp" 22 | 23 | #define DATA_SIZE 4096 // 2**12 24 | // #define DATA_SIZE 16384 // 2**14 25 | // #define DATA_SIZE 65536 // 2**16 26 | // #define DATA_SIZE 262144 // 2**18 27 | 28 | // using namespace std::chrono_literals; // NOLINT 29 | 30 | bool check_vadd( 31 | const unsigned int *in1, // Read-Only Vector 1 32 | const unsigned int *in2, // Read-Only Vector 2 33 | const unsigned int *out // Read-Only Result 34 | ) { 35 | bool match = true; 36 | // no need to iterate twice through the loop, math's the same 37 | for (int i = 0 ; i < DATA_SIZE ; i++) { 38 | unsigned int expected = in1[i]+in2[i]; 39 | if (out[i] != expected) { 40 | // std::cout << "Error: Result mismatch" << std::endl; 41 | // std::cout << "i = " << i << " CPU result = " 42 | // << expected << " Device result = " << out[i] << std::endl; 43 | match = false; 44 | break; 45 | } 46 | } 47 | return match; 48 | } 49 | 50 | int main(int argc, char * argv[]) { 51 | 52 | // Application variables 53 | unsigned int in1[DATA_SIZE]; 54 | unsigned int in2[DATA_SIZE]; 55 | unsigned int out[DATA_SIZE]; 56 | 57 | // randomize the vectors used 58 | for (int i = 0 ; i < DATA_SIZE ; i++) { 59 | in1[i] = rand() % DATA_SIZE; // NOLINT 60 | in2[i] = rand() % DATA_SIZE; // NOLINT 61 | out[i] = 0; 62 | } 63 | 64 | // Add vectors 65 | vadd(in1, in2, out, DATA_SIZE); // function subject to be accelerated 66 | 67 | // Validate operation 68 | check_vadd(in1, in2, out); 69 | 70 | return 0; 71 | } 72 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | // TRIPCOUNT identifier 19 | const int c_size = DATA_SIZE; 20 | 21 | extern "C" { 22 | void vadd( 23 | const unsigned int *in1, // Read-Only Vector 1 24 | const unsigned int *in2, // Read-Only Vector 2 25 | unsigned int *out, // Output Result 26 | int size // Size in integer 27 | ) 28 | { 29 | for (int z = 0; z < size; ++z) { 30 | #pragma HLS loop_tripcount min = c_size max = c_size 31 | for (int j = 0; j < size; ++j) { // stupidly iterate over 32 | // it to generate load 33 | #pragma HLS loop_tripcount min = c_size max = c_size 34 | for (int i = 0; i < size; ++i) { 35 | #pragma HLS loop_tripcount min = c_size max = c_size 36 | out[i] = in1[i] + in2[i]; 37 | } 38 | } 39 | } 40 | } 41 | } 42 | -------------------------------------------------------------------------------- /nodes/triplevadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(vadd_publisher) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(std_msgs REQUIRED) 16 | find_package(ament_vitis) 17 | find_package(tracetools REQUIRED) 18 | find_package(tracetools_acceleration REQUIRED) 19 | 20 | add_executable(vadd_publisher src/vadd_publisher.cpp src/vadd.cpp) 21 | target_include_directories(vadd_publisher PUBLIC include) 22 | ament_target_dependencies(vadd_publisher rclcpp std_msgs tracetools tracetools_acceleration) 23 | 24 | if(ROS_ACCELERATION) 25 | if (ROS_VITIS) 26 | # C simulation and synthesis 27 | vitis_hls_generate_tcl( 28 | PROJECT 29 | project_vadd_publisher 30 | SRC 31 | src/vadd.cpp 32 | HEADERS 33 | include 34 | TESTBENCH 35 | src/testbench.cpp 36 | TOPFUNCTION 37 | vadd 38 | CLOCK 39 | 4 40 | SYNTHESIS 41 | ) 42 | endif() # ROS_VITIS 43 | if (ROS_ONEAPI) 44 | 45 | endif() # ROS_ONEAPI 46 | endif() # ROS_ACCELERATION 47 | 48 | install(TARGETS 49 | vadd_publisher 50 | DESTINATION lib/${PROJECT_NAME} 51 | ) 52 | 53 | if(BUILD_TESTING) 54 | find_package(ament_lint_auto REQUIRED) 55 | ament_lint_auto_find_test_dependencies() 56 | endif() 57 | 58 | # Install launch files. 59 | install(DIRECTORY 60 | launch 61 | DESTINATION share/${PROJECT_NAME} 62 | ) 63 | 64 | ament_package() 65 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/include/vadd.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Author: Víctor Mayoral Vilches 5 | 6 | #ifndef XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 7 | #define XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 8 | 9 | extern "C" { 10 | void vadd( 11 | const unsigned int *in1, // Read-Only Vector 1 12 | const unsigned int *in2, // Read-Only Vector 2 13 | unsigned int *out, // Output Result 14 | int size // Size in integer 15 | ); 16 | } // extern "C" 17 | 18 | #endif // XILINX_EXAMPLES_VADD_PUBLISHER_INCLUDE_VADD_HPP_ 19 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/launch/vadd_capture.launch.py: -------------------------------------------------------------------------------- 1 | # ____ ____ 2 | # / /\/ / 3 | # /___/ \ / Copyright (c) 2021, Xilinx®. 4 | # \ \ \/ Author: Víctor Mayoral Vilches 5 | # \ \ 6 | # / / 7 | # /___/ /\ 8 | # \ \ / \ 9 | # \___\/\___\ 10 | # 11 | # 12 | # Licensed under the Apache License, Version 2.0 (the "License"); 13 | # you may not use this file except in compliance with the License. 14 | # You may obtain a copy of the License at 15 | # 16 | # http://www.apache.org/licenses/LICENSE-2.0 17 | # 18 | # Unless required by applicable law or agreed to in writing, software 19 | # distributed under the License is distributed on an "AS IS" BASIS, 20 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | # See the License for the specific language governing permissions and 22 | # limitations under the License. 23 | 24 | """Example launch file for a profiling analysis.""" 25 | 26 | from launch import LaunchDescription 27 | from launch_ros.actions import Node 28 | from tracetools_launch.action import Trace 29 | from tracetools_trace.tools.names import DEFAULT_CONTEXT 30 | from tracetools_trace.tools.names import DEFAULT_EVENTS_ROS 31 | 32 | 33 | def generate_launch_description(): 34 | return LaunchDescription( 35 | [ 36 | Trace( 37 | session_name="vadd_capture", 38 | events_ust=[ 39 | "ros2_acceleration:vadd_pre", 40 | "ros2_acceleration:vadd_post", 41 | ] 42 | + DEFAULT_EVENTS_ROS, 43 | events_kernel=[ 44 | "sched_switch", 45 | ], 46 | # context_names=[ 47 | # "ip", 48 | # ] 49 | # + DEFAULT_CONTEXT, 50 | ), 51 | Node( 52 | package="vadd_publisher", 53 | executable="vadd_publisher", 54 | # arguments=["do_more"], 55 | output="screen", 56 | ), 57 | ] 58 | ) 59 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | vadd_publisher 5 | 0.3.0 6 | A a trivial vector-add ROS 2 publisher. Adds 7 | two inputs to a vector in a loop and publishes on the go at 8 | 10 Hz. 9 | 10 | Víctor Mayoral Vilches 11 | Apache License 2.0 12 | Víctor Mayoral Vilches 13 | 14 | ament_cmake 15 | 16 | rclcpp 17 | std_msgs 18 | ament_vitis 19 | tracetools 20 | tracetools_acceleration 21 | 22 | ament_lint_auto 23 | ament_lint_common 24 | 25 | 26 | ament_cmake 27 | 28 | 29 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/src/testbench.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | */ 15 | 16 | #include // NOLINT 17 | #include 18 | #include 19 | #include 20 | 21 | #include "vadd.hpp" 22 | 23 | #define DATA_SIZE 4096 // 2**12 24 | // #define DATA_SIZE 16384 // 2**14 25 | // #define DATA_SIZE 65536 // 2**16 26 | // #define DATA_SIZE 262144 // 2**18 27 | 28 | // using namespace std::chrono_literals; // NOLINT 29 | 30 | bool check_vadd( 31 | const unsigned int *in1, // Read-Only Vector 1 32 | const unsigned int *in2, // Read-Only Vector 2 33 | const unsigned int *out // Read-Only Result 34 | ) { 35 | bool match = true; 36 | // no need to iterate twice through the loop, math's the same 37 | for (int i = 0 ; i < DATA_SIZE ; i++) { 38 | unsigned int expected = in1[i]+in2[i]; 39 | if (out[i] != expected) { 40 | // std::cout << "Error: Result mismatch" << std::endl; 41 | // std::cout << "i = " << i << " CPU result = " 42 | // << expected << " Device result = " << out[i] << std::endl; 43 | match = false; 44 | break; 45 | } 46 | } 47 | return match; 48 | } 49 | 50 | int main(int argc, char * argv[]) { 51 | 52 | // Application variables 53 | unsigned int in1[DATA_SIZE]; 54 | unsigned int in2[DATA_SIZE]; 55 | unsigned int out[DATA_SIZE]; 56 | 57 | // randomize the vectors used 58 | for (int i = 0 ; i < DATA_SIZE ; i++) { 59 | in1[i] = rand() % DATA_SIZE; // NOLINT 60 | in2[i] = rand() % DATA_SIZE; // NOLINT 61 | out[i] = 0; 62 | } 63 | 64 | // Add vectors 65 | vadd(in1, in2, out, DATA_SIZE); // function subject to be accelerated 66 | 67 | // Validate operation 68 | check_vadd(in1, in2, out); 69 | 70 | return 0; 71 | } 72 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/src/u200.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_u200_xdma_201830_2 2 | debug=1 3 | save-temps=1 4 | 5 | [connectivity] 6 | nk=vadd:1:vadd_1 7 | sp=vadd_1.in1:DDR[1] 8 | sp=vadd_1.in2:DDR[2] 9 | sp=vadd_1.out:DDR[1] 10 | 11 | [profile] 12 | data=all:all:all 13 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/src/vadd.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2021, Xilinx®. 5 | \ \ \/ Author: Víctor Mayoral Vilches 6 | \ \ 7 | / / 8 | /___/ /\ 9 | \ \ / \ 10 | \___\/\___\ 11 | 12 | Inspired by the Vector-Add example. 13 | See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 14 | 15 | */ 16 | 17 | #define DATA_SIZE 4096 18 | 19 | // TRIPCOUNT identifier 20 | const int c_size = DATA_SIZE; 21 | 22 | extern "C" { 23 | void vadd( 24 | const unsigned int *in1, // Read-Only Vector 1 25 | const unsigned int *in2, // Read-Only Vector 2 26 | unsigned int *out, // Output Result 27 | int size // Size in integer 28 | ) 29 | { 30 | for (int i = 0; i < size; ++i) { 31 | #pragma HLS loop_tripcount min = c_size max = c_size 32 | out[i] = in1[i] + in2[i]; 33 | } 34 | } 35 | } 36 | -------------------------------------------------------------------------------- /nodes/vadd_publisher/src/zcu102.cfg: -------------------------------------------------------------------------------- 1 | platform=xilinx_zcu102_base_202020_1 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | -------------------------------------------------------------------------------- /nodes/xrt_examples/streaming_k2k_mm_xrt/include/logger.h: -------------------------------------------------------------------------------- 1 | /** 2 | * Copyright (C) 2019-2021 Xilinx, Inc 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"). You may 5 | * not use this file except in compliance with the License. A copy of the 6 | * License is located at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT 12 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the 13 | * License for the specific language governing permissions and limitations 14 | * under the License. 15 | */ 16 | #ifndef LOGGER_H_ 17 | #define LOGGER_H_ 18 | 19 | #include 20 | #include 21 | #include 22 | #include 23 | 24 | #define ENABLE_LOG_TOFILE 1 25 | #define ENABLE_LOG_TIME 1 26 | 27 | // global logging 28 | #define LogInfo(desc, ...) sda::LogWrapper(0, __FILE__, __LINE__, desc, ##__VA_ARGS__) 29 | #define LogWarn(desc, ...) sda::LogWrapper(1, __FILE__, __LINE__, desc, ##__VA_ARGS__) 30 | #define LogError(desc, ...) sda::LogWrapper(2, __FILE__, __LINE__, desc, ##__VA_ARGS__) 31 | 32 | using namespace std; 33 | 34 | namespace sda { 35 | 36 | enum LOGTYPE { etInfo, etWarning, etError }; 37 | 38 | // string 39 | string& ltrim(string& s); 40 | string& rtrim(string& s); 41 | string& trim(string& s); 42 | string GetFileExt(const string& s); 43 | string GetFileTitleOnly(const string& s); 44 | 45 | string ToLower(const string& s); 46 | string ToUpper(const string& s); 47 | 48 | // time 49 | string GetTimeStamp(); 50 | 51 | // paths 52 | string GetApplicationPath(); 53 | 54 | // debug 55 | template 56 | void PrintPOD(const vector& pod, size_t display_count = 0, const int precision = 4) { 57 | size_t count = pod.size(); 58 | if (display_count > 0) count = std::min(pod.size(), display_count); 59 | 60 | for (size_t i = 0; i < count; i++) { 61 | cout << std::setprecision(precision) << pod[i] << ", "; 62 | } 63 | cout << endl; 64 | } 65 | 66 | // logging 67 | void LogWrapper(int etype, const char* file, int line, const char* desc, ...); 68 | } 69 | 70 | #endif /* LOGGER_H_ */ 71 | -------------------------------------------------------------------------------- /nodes/xrt_examples/streaming_k2k_mm_xrt/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | streaming_k2k_mm_xrt 5 | 0.3.0 6 | 7 | This example demonstrates how kernels can have memory mapped 8 | inputs along with stream interface from one kernel to another. 9 | 10 | Specifically, this is a ROS native version of a simple kernel to 11 | kernel streaming Vector Add and Vector Multiply C Kernel design with 12 | 2 memory mapped input to kernel 1, 1 Stream output from kernel 13 | 1 to input of kernel 2, 1 memory mapped input to kernel 2, and 14 | 1 memory mapped output that demonstrates on how to process a 15 | stream of data for computation between two kernels using XRT 16 | Native APIs. This design also illustrates how to set FIFO depth 17 | for AXIS connections i.e. for the stream connecting the two kernels. 18 | 19 | Package's inspired by https://github.com/Xilinx/Vitis_Accel_Examples/tree/master/host_xrt/streaming_k2k_mm_xrt. 20 | 21 | Víctor Mayoral Vilches 22 | Apache License 2.0 23 | Víctor Mayoral Vilches 24 | 25 | ament_cmake 26 | ament_vitis 27 | 28 | vitis_common 29 | acceleration_firmware_kv260 30 | 31 | ament_lint_auto 32 | ament_lint_common 33 | 34 | 35 | ament_cmake 36 | 37 | 38 | -------------------------------------------------------------------------------- /nodes/xrt_examples/streaming_k2k_mm_xrt/src/krnl_stream_vadd.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * Copyright (C) 2019-2021 Xilinx, Inc 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"). You may 5 | * not use this file except in compliance with the License. A copy of the 6 | * License is located at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT 12 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the 13 | * License for the specific language governing permissions and limitations 14 | * under the License. 15 | */ 16 | #include "ap_axi_sdata.h" 17 | #include "ap_int.h" 18 | #include "hls_stream.h" 19 | 20 | #define DWIDTH 32 21 | 22 | typedef ap_axiu pkt; 23 | 24 | extern "C" { 25 | void krnl_stream_vadd(int* in1, // Read-Only Vector 1 26 | int* in2, // Read-Only Vector 2 27 | hls::stream& out, // Internal Stream 28 | int size // Size in integer 29 | ) { 30 | vadd: 31 | for (int i = 0; i < size; i++) { 32 | #pragma HLS PIPELINE II = 1 33 | int res = in1[i] + in2[i]; 34 | pkt v; 35 | v.data = res; 36 | out.write(v); 37 | } 38 | } 39 | } 40 | -------------------------------------------------------------------------------- /nodes/xrt_examples/streaming_k2k_mm_xrt/src/krnl_stream_vadd_vmult.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | # Enable profiling of data ports 6 | [profile] 7 | data=all:all:all 8 | 9 | [connectivity] 10 | stream_connect=krnl_stream_vadd_1.out:krnl_stream_vmult_1.in2:64 11 | -------------------------------------------------------------------------------- /nodes/xrt_examples/streaming_k2k_mm_xrt/src/krnl_stream_vmult.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * Copyright (C) 2019-2021 Xilinx, Inc 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"). You may 5 | * not use this file except in compliance with the License. A copy of the 6 | * License is located at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT 12 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the 13 | * License for the specific language governing permissions and limitations 14 | * under the License. 15 | */ 16 | 17 | #include "ap_axi_sdata.h" 18 | #include "ap_int.h" 19 | #include "hls_stream.h" 20 | 21 | #define DWIDTH 32 22 | 23 | typedef ap_axiu pkt; 24 | 25 | extern "C" { 26 | void krnl_stream_vmult(int* in1, // Read-Only Vector 1 27 | hls::stream& in2, // Internal Stream 28 | int* out, // Output Result 29 | int size // Size in integer 30 | ) { 31 | vmult: 32 | for (int i = 0; i < size; i++) { 33 | #pragma HLS PIPELINE II = 1 34 | pkt v2 = in2.read(); 35 | out[i] = in1[i] * v2.data; 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_resize/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(vitis_accelerated_resize) 3 | 4 | # Default to C++14 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 14) 7 | endif() 8 | 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic -Wno-unknown-pragmas) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rclcpp REQUIRED) 15 | find_package(rclcpp_components REQUIRED) 16 | find_package(std_msgs REQUIRED) 17 | find_package(cv_bridge REQUIRED) 18 | find_package(image_transport REQUIRED) 19 | find_package(Threads REQUIRED) 20 | find_package(ament_vitis) 21 | 22 | # add_executable(accelerated_vadd_new 23 | # src/host_new.cpp) 24 | # target_include_directories(accelerated_vadd_new PUBLIC include) 25 | # target_link_libraries(accelerated_vadd_new 26 | # ${OpenCL_LIBRARY} 27 | # pthread) 28 | 29 | find_package(vitis_common REQUIRED) 30 | find_package(OpenCL REQUIRED) 31 | 32 | # accelerated_vadd 33 | add_executable(vitis_accelerated_resize 34 | src/resize_fpga.cpp 35 | src/main.cpp 36 | ) 37 | target_include_directories(vitis_accelerated_resize PUBLIC 38 | include 39 | $ENV{XILINX_HLS}/common/technology/autopilot 40 | $ENV{XILINX_HLS}/include 41 | ) 42 | 43 | target_link_libraries(vitis_accelerated_resize 44 | ${OpenCL_LIBRARY} 45 | pthread 46 | ) 47 | ament_target_dependencies(vitis_accelerated_resize 48 | rclcpp 49 | rclcpp_components 50 | std_msgs 51 | cv_bridge 52 | image_transport 53 | vitis_common ) 54 | 55 | if (ROS_VITIS) 56 | # resize kernel 57 | vitis_acceleration_kernel( 58 | NAME resize_accel 59 | FILE src/xf_resize_accel.cpp 60 | CONFIG cfg/kr260.cfg 61 | INCLUDE 62 | include 63 | ${CMAKE_INSTALL_PREFIX}/include 64 | TYPE 65 | # sw_emu 66 | # hw_emu 67 | hw 68 | LINK 69 | PACKAGE 70 | ) 71 | 72 | endif() # ROS_VITIS 73 | 74 | install(TARGETS 75 | vitis_accelerated_resize 76 | # accelerated_vadd_new 77 | DESTINATION lib/${PROJECT_NAME} 78 | ) 79 | 80 | ament_package() 81 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_resize/cfg/kr260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | [advanced] 6 | param=compiler.skipTimingCheckAndFrequencyScaling=1 7 | 8 | # Enable profiling of data ports 9 | [profile] 10 | data=all:all:all 11 | 12 | # [hls] 13 | # clock=300000000:vadd_accelerated 14 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_resize/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | vitis_accelerated_resize 5 | 0.2.0 6 | An example to showcase how to integrate Vitis Vision Library with KRS. 7 | Here in this example we are showcasing the integration of resize functions. 8 | 9 | 10 | Jasvinder Khurana 11 | Apache License 2.0 12 | Jasvinder Khurana 13 | 14 | ament_cmake 15 | ament_vitis 16 | 17 | acceleration_firmware_kv260 18 | vitis_common 19 | rclcpp 20 | 21 | ament_cmake_auto 22 | ament_vitis 23 | ament_cuda 24 | 25 | cv_bridge 26 | image_geometry 27 | image_transport 28 | rclcpp_components 29 | rcutils 30 | sensor_msgs 31 | tracetools_image_pipeline 32 | 33 | ament_lint_auto 34 | ament_lint_common 35 | 36 | 37 | acceleration_firmware_kv260 38 | 39 | ament_lint_auto 40 | ament_lint_common 41 | 42 | 43 | ament_cmake 44 | 45 | 46 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_resize/src/main.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | ____ ____ 3 | / /\/ / 4 | /___/ \ / Copyright (c) 2024, AMD®. 5 | \ \ \/ Author: Jasvinder Khurana 6 | \ \ 7 | / / Licensed under the Apache License, Version 2.0 (the "License"); 8 | /___/ /\ you may not use this file except in compliance with the License. 9 | \ \ / \ You may obtain a copy of the License at 10 | \___\/\___\ http://www.apache.org/licenses/LICENSE-2.0 11 | 12 | Unless required by applicable law or agreed to in writing, software 13 | distributed under the License is distributed on an "AS IS" BASIS, 14 | WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 15 | See the License for the specific language governing permissions and 16 | limitations under the License. 17 | 18 | */ 19 | 20 | #include // NOLINT 21 | #include 22 | #include 23 | #include 24 | #include 25 | 26 | #include "rclcpp/rclcpp.hpp" 27 | #include "std_msgs/msg/string.hpp" 28 | #include "resize_fpga.hpp" 29 | #include "minimalimagepublisher.hpp" 30 | #include 31 | #include 32 | 33 | using namespace std::chrono_literals; // NOLINT 34 | 35 | int main(int argc, char * argv[]) { 36 | // ROS 2 abstractions 37 | rclcpp::init(argc, argv); 38 | rclcpp::executors::MultiThreadedExecutor executor; 39 | 40 | rclcpp::NodeOptions node_options; 41 | auto node_accelerated_resize = std::make_shared(node_options); 42 | auto node_minimal_publisher = std::make_shared(); 43 | 44 | 45 | executor.add_node(node_minimal_publisher); 46 | executor.add_node(node_accelerated_resize); 47 | executor.spin(); 48 | rclcpp::shutdown(); 49 | 50 | return 0; 51 | } 52 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/cfg/kr260.cfg: -------------------------------------------------------------------------------- 1 | platform=kv260_custom_platform 2 | save-temps=1 3 | debug=1 4 | 5 | [advanced] 6 | param=compiler.skipTimingCheckAndFrequencyScaling=1 7 | 8 | # Enable profiling of data ports 9 | [profile] 10 | data=all:all:all 11 | 12 | # [hls] 13 | # clock=300000000:vadd_accelerated 14 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/data/left.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/vitis_accelerated_examples/vitis_accelerated_stereolbm/data/left.png -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/data/right.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros-acceleration/acceleration_examples/f1f22f8cc659ec5b8402bceb2efc9e2aa37d8d71/vitis_accelerated_examples/vitis_accelerated_stereolbm/data/right.png -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/include/xf_config_params.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2019 Xilinx, Inc. 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #define SAD_WINDOW_SIZE 11 18 | 19 | /* NO_OF_DISPARITIES must be greater than '0' and less than the image width */ 20 | #define NO_OF_DISPARITIES 32 21 | 22 | /* NO_OF_DISPARITIES must not be lesser than PARALLEL_UNITS and NO_OF_DISPARITIES/PARALLEL_UNITS must be a 23 | * non-fractional number */ 24 | #define PARALLEL_UNITS 32 25 | 26 | #define XF_USE_URAM false 27 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/include/xf_stereolbm_config.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2019 Xilinx, Inc. 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | */ 16 | 17 | #ifndef _XF_STEREOBM_CONFIG_H_ 18 | #define _XF_STEREOBM_CONFIG_H_ 19 | 20 | #include "hls_stream.h" 21 | #include "vitis_common/common/xf_common.hpp" 22 | #include "vitis_common/common/xf_utility.hpp" 23 | #include "vitis_common/imgproc/xf_stereolbm.hpp" 24 | #include "xf_config_params.h" 25 | 26 | // Set the input and output pixel depth: 27 | #define IN_TYPE XF_8UC1 28 | #define PTR_IN_WIDTH 8 29 | #define OUT_TYPE XF_16UC1 30 | #define PTR_OUT_WIDTH 16 31 | 32 | // Set the optimization type: 33 | #define NPC XF_NPPC1 34 | 35 | /* config width and height */ 36 | #define WIDTH 1920 37 | #define HEIGHT 1080 38 | #endif // _XF_STEREOBM_CONFIG_H_ 39 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | vitis_accelerated_stereolbm 5 | 0.1.0 6 | An example to showcase integration of Vitis Vision 7 | library function stereolb with KRS. 8 | 9 | 10 | Jasvinder Khurana 11 | Apache License 2.0 12 | Jasvinder Khurana 13 | 14 | ament_cmake 15 | ament_vitis 16 | 17 | acceleration_firmware_kv260 18 | vitis_common 19 | rclcpp 20 | 21 | ament_cmake_auto 22 | ament_vitis 23 | 24 | cv_bridge 25 | image_geometry 26 | image_transport 27 | rclcpp_components 28 | rcutils 29 | sensor_msgs 30 | tracetools_image_pipeline 31 | 32 | ament_lint_auto 33 | ament_lint_common 34 | 35 | 36 | acceleration_firmware_kv260 37 | 38 | ament_lint_auto 39 | ament_lint_common 40 | 41 | 42 | ament_cmake 43 | 44 | 45 | -------------------------------------------------------------------------------- /vitis_accelerated_examples/vitis_accelerated_stereolbm/src/main.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021, Xilinx®. 2 | // All rights reserved 3 | // 4 | // Inspired by the Vector-Add example. 5 | // See https://github.com/Xilinx/Vitis-Tutorials/blob/master/Getting_Started/Vitis 6 | // 7 | 8 | #include // NOLINT 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include "rclcpp/rclcpp.hpp" 15 | #include "std_msgs/msg/string.hpp" 16 | #include "accelerated_node.hpp" 17 | #include "minimalimagepublisher.hpp" 18 | #include 19 | #include 20 | 21 | using namespace std::chrono_literals; // NOLINT 22 | 23 | int main(int argc, char * argv[]) { 24 | // ROS 2 abstractions 25 | rclcpp::init(argc, argv); 26 | rclcpp::executors::MultiThreadedExecutor executor; 27 | 28 | rclcpp::NodeOptions node_options; 29 | auto node_accelerated = std::make_shared(node_options); 30 | auto node_minimal_publisher_left = std::make_shared("left"); 31 | auto node_minimal_publisher_right = std::make_shared("right"); 32 | 33 | 34 | executor.add_node(node_minimal_publisher_left); 35 | executor.add_node(node_minimal_publisher_right); 36 | executor.add_node(node_accelerated); 37 | executor.spin(); 38 | rclcpp::shutdown(); 39 | 40 | return 0; 41 | } 42 | --------------------------------------------------------------------------------