Giter Site home page Giter Site logo

ros-acceleration / acceleration_examples Goto Github PK

View Code? Open in Web Editor NEW
39.0 4.0 19.0 2.92 MB

ROS 2 package examples demonstrating the use of hardware acceleration.

License: Apache License 2.0

CMake 6.17% C++ 48.70% Python 40.05% Tcl 5.08%
hardware-acceleration ros2 fpga gpu

acceleration_examples's Introduction

acceleration_examples

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

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

Quick access

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

ROS 2 Node acceleration examples

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

ROS 2 Graph acceleration examples

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

Quality Declaration

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

acceleration_examples's People

Contributors

alexmarfar avatar dirksavage88 avatar samlei-research avatar vmayoral avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar

acceleration_examples's Issues

Failed to launch hello_xilinx in an emulated KV260

surender@xhdsurender41:/scratch/KRS/krs_ws$ colcon acceleration emulation sw_emu install-kv260
SECURITY WARNING: This class invokes explicitly a shell via the shell=True argument of the Python subprocess library, and uses admin privileges to manage raw disk images. It is the user's responsibility to ensure that all whitespace and metacharacters passed are quoted appropriately to avoid shell injection vulnerabilities.

  • Verified that install/ is available in the current ROS 2 workspace
  • Confirmed availability of raw image file at: /scratch/KRS/krs_ws/acceleration/firmware/select/sd_card.img
  • Finished inspecting raw image, obtained UNITS and STARTSECTOR P1/P2
  • Image mounted successfully at: /tmp/sdcard_img_p2
  • Successfully cleaned up prior overlay ROS 2 workspace at: /tmp/sdcard_img_p2/ros2_ws
  • Copied 'install-kv260' directory as a ROS 2 overlay workspace in the raw image.
  • Umounted the raw image.
  • Generated PMU and QEMU files.
  • Launching emulation...
    cd /scratch/KRS/krs_ws/acceleration/firmware/select/emulation && /proj/xbuilds/SWIP/2020.2_1118_1232/installs/lin64/Vitis/2020.2/bin/launch_emulator -device-family ultrascale -target sw_emu -qemu-args-file /scratch/KRS/krs_ws/acceleration/firmware/select/emulation/qemu_args.txt -pmc-args-file /scratch/KRS/krs_ws/acceleration/firmware/select/emulation/pmu_args.txt -sd-card-image /scratch/KRS/krs_ws/acceleration/firmware/select/sd_card.img -enable-prep-target $*
    Running SW Emulation
    INFO : [LAUNCH_EMULATOR] pl_sim_dir option is not provided.
    Starting QEMU
  • Press for help
    Waiting for QEMU to start. qemu_port 7376
    Qemu_pids 1045781 1045782
    qemu-system-aarch64: -chardev socket,path=./qemu-rport-_pmu@0,server,id=pmu-apu-rp: info: QEMU waiting for connection on: disconnected:unix:./qemu-rport-_pmu@0,server
    QEMU started. qemu_pid=1045781.
    Waiting for PMU to start. Qemu_pids 1045801 1045802
    qemu-system-aarch64: -chardev socket,id=pl-rp,host=127.0.0.1,port=9248,server: info: QEMU waiting for connection on: disconnected:tcp:127.0.0.1:9248,server
    PMC started. pmc_pid=1045801
    Starting PL simulation.Generating PLLauncher commandline
    running PLL Launcher
    qemu-system-aarch64: Could not reopen file: Permission denied
    qemu-system-microblazeel: /pmu@0: Disconnected clk=5263364164 ns

[LAUNCH_EMULATOR] INFO: 13:00:55 : PS-QEMU exited
[LAUNCH_EMULATOR] INFO: 13:00:57 : PS-QEMU exited
[LAUNCH_EMULATOR] INFO: 13:00:57 : PMU/PMC-QEMU exited
[LAUNCH_EMULATOR] INFO: 13:00:57 : Trying to kill PLLauncher forcefully because QEMU exited
[LAUNCH_EMULATOR] INFO: 13:00:57 : PLLauncher exited by force
Please refer PS /simulate logs at /scratch/KRS/krs_ws/acceleration/firmware/kv260/emulation for more details.
DONE!
INFO: Emulation ran successfully
Finalized successfully.

offloaded_doublevadd_publisher build is error out

surender@xhdsurender41:/scratch/KRS/krs_ws$ colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select ament_vitis ros2acceleration offloaded_doublevadd_publisher
Starting >>> ament_vitis
Starting >>> ros2acceleration
Finished <<< ament_vitis [0.60s]
Starting >>> offloaded_doublevadd_publisher
Finished <<< ros2acceleration [0.77s]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
[Processing: offloaded_doublevadd_publisher]
--- stderr: offloaded_doublevadd_publisher
ERROR: The following input file does not exist: /scratch/KRS/krs_ws/build-kv260/offloaded_doublevadd_publisher/vadd.xclbin
---
Finished <<< offloaded_doublevadd_publisher [6min 21s]

Summary: 3 packages finished [6min 22s]
  1 package had stderr output: offloaded_doublevadd_publisher
surender@xhdsurender41:/scratch/KRS/krs_ws$

Unable to generate Benchmarking Graphs from tracedata

Hi @vmayoral,

I am trying to reproduce ROS Perception benchmarking data which is published on KRS Documentation i.e. this with KRS 1.0.

I ran CPU Only ROS Perception application which produced following trace data:

trace_rectify_resize/ust/uid/0/64-bit/
├── index
│   ├── ros2_0.idx
│   ├── ros2_1.idx
│   ├── ros2_2.idx
│   └── ros2_3.idx
├── metadata
├── ros2_0
├── ros2_1
├── ros2_2
└── ros2_3

After this I launched the analysis launch file: https://github.com/ros-acceleration/acceleration_examples/blob/main/graphs/perception/perception_2nodes/launch/analyse_rectify_resize.launch.py

while keeping only
image_pipeline_msg_sets_ms_cpu I have commenting out subsequent message_sets* as we didn't have trace data for gpu, fpga and other scenarios.

After launching the modified launch file, following errors are observed:

root@kria:~/.ros/tracing# ros2 launch perception_2nodes analyse_rectify_resize.launch.py 
[INFO] [launch]: All log files can be found below /root/.ros/log/2022-08-08-11-55-00-972134-kria-347256
[INFO] [launch]: Default logging verbosity is set to INFO
/usr/lib/python3/dist-packages/numpy/core/fromnumeric.py:3440: RuntimeWarning: Mean of empty slice.
  return _methods._mean(a, axis=axis, dtype=dtype,
/usr/lib/python3/dist-packages/numpy/core/_methods.py:189: RuntimeWarning: invalid value encountered in double_scalars
  ret = ret.dtype.type(ret / rcount)
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught exception when trying to load file of format [py]: zero-size array to reduction operation minimum which has no identity

As per trace_tools architecture doc , there is a conversion required which generateds data model from tracedata i.e. converted file.
if we run the launch file by passing converted file path, this leads to below error:

root@kria:~/.ros/tracing# ros2 launch perception_2nodes analyse_rectify_resize.launch.py 
[INFO] [launch]: All log files can be found below /root/.ros/log/2022-08-08-12-19-32-941406-kria-348467
[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught exception when trying to load file of format [py]: list index out of range

Can you please help in understanding what might be missing? Also can you share any example tracedata on which this analyze launch file works well? this would be helpful in comparison and narrowing down the issue.

Building offloaded_doublevadd_publisher failed

#steps followed from KRS Documentation and trying to build offloaded_doublevadd_publisher package, below is the error log.

surender@xhdsurender41:/scratch/krs_ws$ colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select ament_vitis ros2acceleration offloaded_doublevadd_publisher

Starting >>> ament_vitis
Starting >>> ros2acceleration
Finished <<< ament_vitis [0.55s]
Starting >>> offloaded_doublevadd_publisher
[0.998s] WARNING:colcon.colcon_core.shell:The following packages are in the workspace but haven't been built:

  • vitis_common
    They are being used from the following locations instead:

  • /scratch/krs_ws/install
    To suppress this warning ignore these packages in the workspace:
    --packages-ignore vitis_common
    Finished <<< ros2acceleration [0.57s]
    **--- stderr: offloaded_doublevadd_publisher
    CMake Error at CMakeLists.txt:18 (find_package):
    By not providing "Findvitis_common.cmake" in CMAKE_MODULE_PATH this project
    has asked CMake to find a package configuration file provided by
    "vitis_common", but CMake did not find one.

    Could not find a package configuration file provided by "vitis_common" with
    any of the following names:

    vitis_commonConfig.cmake
    vitis_common-config.cmake

    Add the installation prefix of "vitis_common" to CMAKE_PREFIX_PATH or set
    "vitis_common_DIR" to a directory containing one of the above files. If
    "vitis_common" provides a separate development package or SDK, be sure it
    has been installed.


Failed <<< offloaded_doublevadd_publisher [0.75s, exited with code 1]**

Summary: 2 packages finished [1.47s]
1 package failed: offloaded_doublevadd_publisher
1 package had stderr output: offloaded_doublevadd_publisher

The following input file does not exist: vadd.xclbin

Hey,

so I am playing with the FPGA acceleration following this example and first I had a problem with

colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select ament_vitis ros2acceleration offloaded_doublevadd_publisher

[0.188s] colcon.colcon_core.verb WARNING Some selected packages are already built in one or more underlay workspaces:
	'ament_vitis' is in: /home/andrzej/code_workspace/krs_ws/install
	'ros2acceleration' is in: /home/andrzej/code_workspace/krs_ws/install
	'offloaded_doublevadd_publisher' is in: /home/andrzej/code_workspace/krs_ws/install
If a package in a merged underlay workspace is overridden and it installs headers, then all packages in the overlay must sort their include directories by workspace order. Failure to do so may result in build failures or undefined behavior at run time.
If the overridden package is used by another package in any underlay, then the overriding package in the overlay must be API and ABI compatible or undefined behavior at run time may occur.

If you understand the risks and want to override a package anyways, add the following to the command line:
	--allow-overriding ament_vitis offloaded_doublevadd_publisher ros2acceleration

This may be promoted to an error in a future release of colcon-core.
Starting >>> ament_vitis
Starting >>> ros2acceleration
Finished <<< ament_vitis [0.31s]                                                        
Starting >>> offloaded_doublevadd_publisher
[0.505s] colcon.colcon_core.shell WARNING The following packages are in the workspace but haven't been built:
- vitis_common
They are being used from the following locations instead:
- /home/andrzej/code_workspace/krs_ws/install
To suppress this warning ignore these packages in the workspace:
--packages-ignore vitis_common
--- stderr: offloaded_doublevadd_publisher                                                               
CMake Error at CMakeLists.txt:18 (find_package):
  By not providing "Findvitis_common.cmake" in CMAKE_MODULE_PATH this project
  has asked CMake to find a package configuration file provided by
  "vitis_common", but CMake did not find one.

  Could not find a package configuration file provided by "vitis_common" with
  any of the following names:

    vitis_commonConfig.cmake
    vitis_common-config.cmake

  Add the installation prefix of "vitis_common" to CMAKE_PREFIX_PATH or set
  "vitis_common_DIR" to a directory containing one of the above files.  If
  "vitis_common" provides a separate development package or SDK, be sure it
  has been installed.


make: *** [Makefile:296: cmake_check_build_system] Error 1
---
Failed   <<< offloaded_doublevadd_publisher [0.52s, exited with code 2]
Aborted  <<< ros2acceleration [0.87s]

Summary: 1 package finished [0.99s]
  1 package failed: offloaded_doublevadd_publisher
  1 package aborted: ros2acceleration
  1 package had stderr output: offloaded_doublevadd_publisher

so there is lack of *.cmake files, but I figured that in order to solve this problem I can just add vitils_common

colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select ament_vitis ros2acceleration offloaded_doublevadd_publisher vitis_common

everything compiles, despite that the following error shows up

ERROR: The following input file does not exist: /home/andrzej/code_workspace/krs_ws/build-kv260/offloaded_doublevadd_publisher/vadd.xclbin

Then when I run on kv260

ros2 run offloaded_doublevadd_publisher offloaded_doublevadd_publisher

the following error appears

INFO: Found Xilinx Platform
ERROR: vadd.xclbin xclbin not available please build

any hints on where this error is coming from or from where the file vadd.xclbin is coming from?

Build fail for vadd_publisher

I am following the KRS documentation and facing build issue in kv260 example:

xhdjasvinde41:/scratch/Work/Ros2/krs_ws $ colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select ament_vitis vadd_publisher
Starting >>> ament_vitis
Finished <<< ament_vitis [0.21s]
Starting >>> vadd_publisher
--- stderr: vadd_publisher
CMake Error at CMakeLists.txt:2 (project):
  The CMAKE_C_COMPILER:

    /scratch/Work/Ros2/krs_ws/install/../acceleration/firmware/kv260/../vitis/gnu/aarch64/lin/aarch64-linux/bin/aarch64-linux-gnu-gcc

  is not a full path to an existing compiler tool.

  Tell CMake where to find the compiler by setting either the environment
  variable "CC" or the CMake cache entry CMAKE_C_COMPILER to the full path to
  the compiler, or to the compiler name if it is in the PATH.


CMake Error at CMakeLists.txt:2 (project):
  The CMAKE_CXX_COMPILER:

    /scratch/Work/Ros2/krs_ws/install/../acceleration/firmware/kv260/../vitis/gnu/aarch64/lin/aarch64-linux/bin/aarch64-linux-gnu-g++

  is not a full path to an existing compiler tool.

  Tell CMake where to find the compiler by setting either the environment
  variable "CXX" or the CMake cache entry CMAKE_CXX_COMPILER to the full path
  to the compiler, or to the compiler name if it is in the PATH.


---
Failed   <<< vadd_publisher [0.32s, exited with code 1]

Summary: 1 package finished [0.74s]
  1 package failed: vadd_publisher
  1 package had stderr output: vadd_publisher 

cmake is not able to find a compiler. Can you guide what would be causing the issue.

Topics '/camera/image_raw' and '/camera_info' do not appear to be synchronized

After launching rectify_resize_fpga_streamlined application using below command, duplicate node has been observed on KR260. This seems to be breaking the functionality of the app
We observed only a 4-5 frames during 5 minutes of testing and most of the time there is no message published on /resize topic,.

ros2 launch perception_2nodes trace_rectify_resize_fpga_streamlined.launch.py

[INFO] [launch]: All log files can be found below /root/.ros/log/2022-06-27-18-31-27-439445-kria-3015
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [tracetools_launch.action]: Writing tracing session to: /root/.ros/tracing/trace_rectify_resize_fpga_streamlined
[INFO] [rectify_resize_fpga_streamlined_node-1]: process started with pid [3028]
[rectify_resize_fpga_streamlined_node-1] [WARN] [1656354692.192969458] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[rectify_resize_fpga_streamlined_node-1] [WARN] [1656354705.248085520] [rectify_resize_fpga_streamlined_node]: [image_transport] Topics '/camera/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[rectify_resize_fpga_streamlined_node-1] 	Image messages received:      3
[rectify_resize_fpga_streamlined_node-1] 	CameraInfo messages received: 0
[rectify_resize_fpga_streamlined_node-1] 	Synchronized pairs:           0
[rectify_resize_fpga_streamlined_node-1] [WARN] [1656354937.192651937] [rectify_resize_fpga_streamlined_node]: [image_transport] Topics '/camera/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[rectify_resize_fpga_streamlined_node-1] 	Image messages received:      6
[rectify_resize_fpga_streamlined_node-1] 	CameraInfo messages received: 17
[rectify_resize_fpga_streamlined_node-1] 	Synchronized pairs:           5 

below are the list of nodes observed

ubuntu@kria:~$ ros2 node list
WARNING: Be aware that are nodes in the graph that share an exact name, this can have unintended side effects.
/rectify_resize_fpga_streamlined_node
/rectify_resize_fpga_streamlined_node

It is unclear to me if this duplication of nodes can cause synchronization issue.
Can you please help in resolving?

Not able to run emulation

I am trying to run Emulation for kv260, but I get below error:

[14:11 jasvinde@xhdjasvinde41 krs_ws] > colcon acceleration emulation sw_emu install-kv260
WARNING:colcon.colcon_mixin.mixin:Mixin 'zcu102' from file '/home/jasvinde/.colcon/mixin/zcu102/zcu102.mixin' is overwriting another mixin with the same name
WARNING:colcon.colcon_mixin.mixin:Mixin 'zcu102-debug' from file '/home/jasvinde/.colcon/mixin/zcu102/zcu102.mixin' is overwriting another mixin with the same name
SECURITY WARNING: This class invokes explicitly a shell via the shell=True argument of the Python subprocess library, and uses admin privileges to manage raw disk images. It is the user's responsibility to ensure that all whitespace and metacharacters passed are quoted appropriately to avoid shell injection vulnerabilities.
- Verified that install/ is available in the current ROS 2 workspace
- Confirmed availability of raw image file at: /scratch/Work/Ros2/krs_ws/acceleration/firmware/select/sd_card.img
- Finished inspecting raw image, obtained UNITS and STARTSECTOR P1/P2
- Image mounted successfully at: /tmp/sdcard_img_p2
No prior overlay ROS 2 workspace found at: /tmp/sdcard_img_p2/ros2_ws, creating it.
- Copied 'install-kv260' directory as a ROS 2 overlay workspace in the raw image.
- Umounted the raw image.
- Generated PMU and QEMU files.
- Launching emulation...
cd /scratch/Work/Ros2/krs_ws/acceleration/firmware/select/emulation && /proj/xbuilds/SWIP/2020.2_1118_1232/installs/lin64/Vitis/2020.2/bin/launch_emulator -device-family ultrascale -target sw_emu -qemu-args-file /scratch/Work/Ros2/krs_ws/acceleration/firmware/select/emulation/qemu_args.txt -pmc-args-file /scratch/Work/Ros2/krs_ws/acceleration/firmware/select/emulation/pmu_args.txt -sd-card-image /scratch/Work/Ros2/krs_ws/acceleration/firmware/select/sd_card.img -enable-prep-target $*
Running SW Emulation
INFO :  [LAUNCH_EMULATOR] pl_sim_dir option is not provided.
Starting QEMU
 - Press <Ctrl-a h> for help
Waiting for QEMU to start. qemu_port 8968
Qemu_pids 2200966 2200967
qemu-system-aarch64: -chardev socket,path=./qemu-rport-_pmu@0,server,id=pmu-apu-rp: info: QEMU waiting for connection on: disconnected:unix:./qemu-rport-_pmu@0,server
QEMU started. qemu_pid=2200966.
Waiting for PMU to start. Qemu_pids 2200970 2200971
qemu-system-aarch64: -chardev socket,id=pl-rp,host=127.0.0.1,port=7783,server: info: QEMU waiting for connection on: disconnected:tcp:127.0.0.1:7783,server
PMC started. pmc_pid=2200970
Starting PL simulation.Generating PLLauncher commandline
running PLL Launcher
qemu-system-aarch64: Could not reopen file: Permission denied
qemu-system-microblazeel: /pmu@0: Disconnected clk=5517356585 ns

[LAUNCH_EMULATOR] INFO: 14:11:45 : PMU/PMC-QEMU  exited
[LAUNCH_EMULATOR] INFO: 14:11:47 : PS-QEMU exited
[LAUNCH_EMULATOR] INFO: 14:11:47 : PMU/PMC-QEMU exited
[LAUNCH_EMULATOR] INFO: 14:11:47 : Trying to kill PLLauncher forcefully because QEMU exited
[LAUNCH_EMULATOR] INFO: 14:11:47 : PLLauncher exited by force
Please refer PS /simulate logs at /scratch/Work/Ros2/krs_ws/acceleration/firmware/kv260/emulation for more details.
DONE!
INFO: Emulation ran successfully

I have executed below steps to run emulation:

509  [30/08 14:06:13] source /<path_to_vitis>/Vitis/2020.2/settings64.sh
  510  [30/08 14:06:25] source /opt/ros/foxy/setup.bash
  511  [30/08 14:06:38] export PATH="/usr/bin":$PATH
  512  [30/08 14:08:43] colcon acceleration select kv260
  513  [30/08 14:09:02] colcon acceleration list
  514  [30/08 14:09:58] source install-kv260/setup.bash
  515  [30/08 14:10:01] colcon acceleration list
  516  [30/08 14:10:16] colcon acceleration select kv260
  517  [30/08 14:10:19] colcon acceleration list
  518  [30/08 14:10:37] colcon build --build-base=build-kv260 --install-base=install-kv260 --merge-install --mixin kv260 --packages-select publisher_xilinx
  519  [30/08 14:10:47] colcon acceleration linux vanilla
  520  [30/08 14:11:34] colcon acceleration emulation sw_emu install-kv260

Please guide what possibly I am doing wrong.

Issues due to the tracepoint size fields

Since the tracetools_benchmark and tracetools_image_pipeline packages from robotperf/benchmarks and ros-acceleration/image_pipeline respectively have been modified to include two new fields, some files need to be updated in acceleration_examples packages

Failed to Get Synthesis Report

I am trying to get synthesis report for simple_adder accelerator, but it is not executing C Simulation. Please see logs below

jasvinder@jasvinder-ubuntu:~/krs_ws$ colcon acceleration list
kv260*
jasvinder@jasvinder-ubuntu:~/krs_ws$ colcon build  --merge-install --build-base=build-kv260 --install-base=install-kv260 --mixin kv260 --packages-select simple_adder
Starting >>> simple_adder
[0.821s] WARNING:colcon.colcon_core.shell:The following packages are in the workspace but haven't been built:
- ament_vitis
They are being used from the following locations instead:
- /home/jasvinder/krs_ws/install
To suppress this warning ignore these packages in the workspace:
--packages-ignore ament_vitis
Finished <<< simple_adder [7.97s]                     

Summary: 1 package finished [8.38s]
jasvinder@jasvinder-ubuntu:~/krs_ws$ colcon acceleration hls simple_adder
 Project:  project_simpleadder1
 Path:  /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1
 	- Solution:  solution_4ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
 Project:  project_simpleadder2
 Path:  /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder2
 	- Solution:  solution_4ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
 	- Solution:  solution_10ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
jasvinder@jasvinder-ubuntu:~/krs_ws$ colcon acceleration hls simple_adder --run
Found Tcl script "project_simpleadder1.tcl" for package: simple_adder
Executing /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1.tcl
Found Tcl script "project_simpleadder2.tcl" for package: simple_adder
Executing /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder2.tcl
 Project:  project_simpleadder1
 Path:  /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1
 	- Solution:  solution_4ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
 Project:  project_simpleadder2
 Path:  /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder2
 	- Solution:  solution_4ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
 	- Solution:  solution_10ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
jasvinder@jasvinder-ubuntu:~/krs_ws$ colcon acceleration hls simple_adder --synthesis-report
 Project:  project_simpleadder1
 Path:  /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1
 	- Solution:  solution_4ns
 		- C Simulation:               Not Run
 		- C Synthesis:                Not Run
 		- C/RTL Co-simulation:        Not Run
		- Export:
 			- IP Catalog:         Not Run
 			- System Generator:   Not Run
 			- Export Evaluation:  Not Run
		- Synthesis report: /home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1/solution_4ns/syn/report/simple_adder_csynth.rpt
[0.537s] ERROR:colcon:colcon acceleration: [Errno 2] No such file or directory: '/home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1/solution_4ns/syn/report/simple_adder_csynth.rpt'
Traceback (most recent call last):
  File "/usr/lib/python3/dist-packages/colcon_core/command.py", line 528, in verb_main
    rc = context.args.main(context=context)
  File "/home/jasvinder/krs_ws/install/lib/python3.8/site-packages/colcon_acceleration/subverb/hls.py", line 495, in main
    self.print_status_solution(s, configuration, context)
  File "/home/jasvinder/krs_ws/install/lib/python3.8/site-packages/colcon_acceleration/subverb/hls.py", line 273, in print_status_solution
    with open(csyn_path,'r') as f:
FileNotFoundError: [Errno 2] No such file or directory: '/home/jasvinder/krs_ws/build-kv260/simple_adder/project_simpleadder1/solution_4ns/syn/report/simple_adder_csynth.rpt'

Please guide for possible issue.

Observing Error messages on all four: CPU Only, FPGA, Integrated and streamline applications in ROS Perception

Following error messages has been observed while running any of the above four apps from ROS Perception:
while the output is observed on respective topics as expected.

`root@kria:/home/ubuntu/install-kr260-ubuntu/lib# ros2 launch perception_2nodes trace_rectify_resize.launch.py
[INFO] [launch]: All log files can be found below /root/.ros/log/2022-06-27-19-11-14-384088-kria-4880
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [tracetools_launch.action]: Writing tracing session to: /root/.ros/tracing/trace_rectify_resize
[INFO] [component_container-1]: process started with pid [4894]
[component_container-1] [INFO] [1656357075.189531890] [perception_container]: Load Library: /home/ubuntu/install-kr260-ubuntu/lib/librectify.so
[component_container-1] [INFO] [1656357075.554523540] [perception_container]: Found class: rclcpp_components::NodeFactoryTemplate<image_proc::RectifyNode>
[component_container-1] [INFO] [1656357075.554690732] [perception_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<image_proc::RectifyNode>
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/rectify_node' in container '/perception_container'
[component_container-1] [INFO] [1656357075.624117536] [perception_container]: Load Library: /home/ubuntu/install-kr260-ubuntu/lib/libresize.so
[component_container-1] [INFO] [1656357075.635588661] [perception_container]: Found class: rclcpp_components::NodeFactoryTemplate<image_proc::ResizeNode>
[component_container-1] [INFO] [1656357075.635757303] [perception_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<image_proc::ResizeNode>
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/resize/resize_node' in container '/perception_container'

[component_container-1] 2022-06-27 19:11:35.263 [RTPS_MSG_IN Error] (ID:281473374806048) Problem reserving CacheChange in reader: 01.0f.c4.59.1e.13.e2.a3.01.00.00.00|0.0.2f.4 -> Function processDataMsg
[component_container-1] 2022-06-27 19:11:35.372 [RTPS_MSG_IN Error] (ID:281473374806048) Problem reserving CacheChange in reader: 01.0f.c4.59.1e.13.e2.a3.01.00.00.00|0.0.1c.4 -> Function processDataMsg
[component_container-1] 2022-06-27 19:11:35.372 [RTPS_MSG_IN Error] (ID:281473374806048) Problem reserving CacheChange in reader: 01.0f.c4.59.1e.13.e2.a3.01.00.00.00|0.0.2f.4 -> Function processDataMsg
[component_container-1] 2022-06-27 19:11:35.421 [RTPS_MSG_IN Error] (ID:281473374806048) Problem reserving CacheChange in reader: 01.0f.c4.59.1e.13.e2.a3.01.00.00.00|0.0.1c.4 -> Function processDataMsg
[component_container-1] 2022-06-27 19:11:35.421 [RTPS_MSG_IN Error] (ID:281473374806048) Problem reserving CacheChange in reader: 01.0f.c4.59.1e.13.e2.a3.01.00.00.00|0.0.2f.4 -> Function processDataMsg
`

Some examples doesn't build

Hi,
I was triying to build the examples, but the build fails due to a missing vitis_common package.
I think that the problem is that in the install instructions (https://xilinx.github.io/KRS/sphinx/build/html/docs/install.html), in the krs_alpha.repos file, the vitis_common repository is missing.
I cloned it manually and now the examples build, so is necessary to add vitis_common repository to the krs_alpha.repos file

regards,
Pedro

Failed to build kv260 sd_card image

Hi,

After successful build of my first Ros2 publisher example I am trying to create image, but it is failing with below error:

jasvinder@jasvinder-ubuntu:~/jassi/ROS2/krs_ws$ colcon acceleration linux vanilla --install-dir install-kv260
SECURITY WARNING: This class invokes explicitly a shell via the shell=True argument of the Python subprocess library, and uses admin privileges to manage raw disk images. It is the user's responsibility to ensure that all whitespace and metacharacters passed are quoted appropriately to avoid shell injection vulnerabilities.
- Creating a new base image using /home/jasvinder/jassi/ROS2/krs_ws/acceleration/firmware/select/rootfs.cpio.gz ...
[sudo] password for jasvinder: 
Something went wrong while creating sd card image.
Review the output: gzip: stdin: unexpected end of file

It is really hard to debug what went wrong. Are there any pointers where to debug for this issue.

PS: I am able to create the image on different Ubuntu machine, but it is failing on my local machine.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.