From bde76f820f51647d87625d575eb4b2f8173ed7dd Mon Sep 17 00:00:00 2001 From: Jaiveer Singh Date: Wed, 5 Apr 2023 18:01:59 -0700 Subject: [PATCH] Isaac ROS 0.30.0 (DP3) --- .gitattributes | 24 + .gitignore | 2 + CONTRIBUTING.md | 14 + LICENSE | 3 +- README.md | 381 ++++++- assets/datasets/.gitignore | 2 + assets/models/.gitignore | 2 + resources/r2b_cafe_sequence.gif | 3 + resources/r2b_datacenter_sequence.gif | 3 + resources/r2b_hallway_sequence.gif | 3 + resources/r2b_hideaway_sequence.gif | 3 + resources/r2b_hope_sequence.gif | 3 + resources/r2b_lounge_sequence.gif | 3 + resources/r2b_mezzanine_sequence.gif | 3 + resources/r2b_storage_sequence.gif | 3 + resources/ros2_benchmark_arch.png | 3 + resources/ros2_benchmark_flow.png | 3 + resources/ros2_benchmark_intro.png | 3 + resources/ros_2_rosbag.png | 3 + .../apriltag_ros_apriltag_graph-agx_orin.json | 1 + ...priltag_ros_apriltag_graph-agx_xavier.json | 1 + .../apriltag_ros_apriltag_graph-orin_nx.json | 1 + ..._ros_apriltag_graph-x86_64_rtx_3060Ti.json | 1 + ...ag_ros_apriltag_graph-x86_64_rtx_4090.json | 1 + .../apriltag_ros_apriltag_node-agx_orin.json | 1 + ...apriltag_ros_apriltag_node-agx_xavier.json | 1 + .../apriltag_ros_apriltag_node-orin_nx.json | 1 + ...g_ros_apriltag_node-x86_64_rtx_3060Ti.json | 1 + ...tag_ros_apriltag_node-x86_64_rtx_4090.json | 1 + results/image_proc_rectify_node-agx_orin.json | 1 + .../image_proc_rectify_node-agx_xavier.json | 1 + results/image_proc_rectify_node-orin_nx.json | 1 + ...e_proc_rectify_node-x86_64_rtx_3060Ti.json | 1 + ...age_proc_rectify_node-x86_64_rtx_4090.json | 1 + ..._transport_h264_decoder_node-agx_orin.json | 1 + ...ransport_h264_decoder_node-agx_xavier.json | 1 + ...e_transport_h264_decoder_node-orin_nx.json | 1 + ...t_h264_decoder_node-x86_64_rtx_3060Ti.json | 1 + ...ort_h264_decoder_node-x86_64_rtx_4090.json | 1 + ..._transport_h264_encoder_node-agx_orin.json | 1 + ...ransport_h264_encoder_node-agx_xavier.json | 1 + ...e_transport_h264_encoder_node-orin_nx.json | 1 + ...t_h264_encoder_node-x86_64_rtx_3060Ti.json | 1 + ...ort_h264_encoder_node-x86_64_rtx_4090.json | 1 + results/stereo_image_proc_graph-agx_orin.json | 1 + .../stereo_image_proc_graph-agx_xavier.json | 1 + ...stereo_image_proc_graph-orin_nano_8gb.json | 1 + ...tereo_image_proc_graph-orin_nano_emul.json | 1 + results/stereo_image_proc_graph-orin_nx.json | 1 + ...eo_image_proc_graph-x86_64_rtx_3060Ti.json | 1 + ...ereo_image_proc_graph-x86_64_rtx_4090.json | 1 + results/stereo_image_proc_node-agx_orin.json | 1 + .../stereo_image_proc_node-agx_xavier.json | 1 + .../stereo_image_proc_node-orin_nano_8gb.json | 1 + ...stereo_image_proc_node-orin_nano_emul.json | 1 + results/stereo_image_proc_node-orin_nx.json | 1 + ...reo_image_proc_node-x86_64_rtx_3060Ti.json | 1 + ...tereo_image_proc_node-x86_64_rtx_4090.json | 1 + ros2_benchmark/CMakeLists.txt | 96 ++ .../include/ros2_benchmark/common.hpp | 38 + .../ros2_benchmark/data_loader_node.hpp | 153 +++ .../include/ros2_benchmark/monitor_node.hpp | 99 ++ .../include/ros2_benchmark/playback_node.hpp | 197 ++++ ros2_benchmark/package.xml | 51 + ros2_benchmark/ros2_benchmark/__init__.py | 36 + .../basic_performance_calculator.py | 218 ++++ .../default_ros2_benchmark_config.yaml | 141 +++ .../ros2_benchmark/ros2_benchmark_config.py | 192 ++++ .../ros2_benchmark/ros2_benchmark_test.py | 939 ++++++++++++++++++ .../ros2_benchmark/utils/__init__.py | 16 + .../ros2_benchmark/utils/cpu_profiler.py | 149 +++ .../ros2_benchmark/utils/image_utility.py | 57 ++ .../ros2_benchmark/utils/nsys_utility.py | 85 ++ .../ros2_benchmark/utils/profiler.py | 82 ++ .../ros2_benchmark/utils/ros2_utility.py | 50 + ros2_benchmark/src/data_loader_node.cpp | 405 ++++++++ ros2_benchmark/src/monitor_node.cpp | 164 +++ ros2_benchmark/src/playback_node.cpp | 588 +++++++++++ ros2_benchmark/test/data_loader_node_pol.py | 120 +++ ros2_benchmark/test/monitor_node_pol.py | 130 +++ ros2_benchmark/test/playback_node_pol.py | 117 +++ ros2_benchmark/test/pol.bag/metadata.yaml | 3 + ros2_benchmark/test/pol.bag/pol.bag_0.db3 | 3 + .../test/pol.bag/pol.bag_0.db3.zstd | 3 + ros2_benchmark_interfaces/CMakeLists.txt | 64 ++ .../msg/TimestampedMessageArray.msg | 25 + .../msg/TopicMessageCount.msg | 24 + .../msg/TopicMessageTimestampArray.msg | 26 + ros2_benchmark_interfaces/package.xml | 45 + .../srv/GetTopicMessageTimestamps.srv | 34 + .../srv/PlayMessages.srv | 65 ++ ros2_benchmark_interfaces/srv/SetData.srv | 31 + .../srv/StartLoading.srv | 45 + .../srv/StartMonitoring.srv | 36 + .../srv/StartRecording.srv | 46 + ros2_benchmark_interfaces/srv/StopLoading.srv | 25 + .../srv/StopRecording.srv | 25 + scripts/apriltag_ros_apriltag_graph.py | 168 ++++ scripts/apriltag_ros_apriltag_node.py | 164 +++ scripts/image_proc_rectify_node.py | 147 +++ scripts/image_transport_h264_decoder_node.py | 161 +++ scripts/image_transport_h264_encoder_node.py | 147 +++ scripts/stereo_image_proc_graph.py | 211 ++++ scripts/stereo_image_proc_node.py | 190 ++++ 104 files changed, 6312 insertions(+), 2 deletions(-) create mode 100644 .gitattributes create mode 100644 .gitignore create mode 100644 CONTRIBUTING.md create mode 100644 assets/datasets/.gitignore create mode 100644 assets/models/.gitignore create mode 100644 resources/r2b_cafe_sequence.gif create mode 100644 resources/r2b_datacenter_sequence.gif create mode 100644 resources/r2b_hallway_sequence.gif create mode 100644 resources/r2b_hideaway_sequence.gif create mode 100644 resources/r2b_hope_sequence.gif create mode 100644 resources/r2b_lounge_sequence.gif create mode 100644 resources/r2b_mezzanine_sequence.gif create mode 100644 resources/r2b_storage_sequence.gif create mode 100644 resources/ros2_benchmark_arch.png create mode 100644 resources/ros2_benchmark_flow.png create mode 100644 resources/ros2_benchmark_intro.png create mode 100644 resources/ros_2_rosbag.png create mode 100644 results/apriltag_ros_apriltag_graph-agx_orin.json create mode 100644 results/apriltag_ros_apriltag_graph-agx_xavier.json create mode 100644 results/apriltag_ros_apriltag_graph-orin_nx.json create mode 100644 results/apriltag_ros_apriltag_graph-x86_64_rtx_3060Ti.json create mode 100644 results/apriltag_ros_apriltag_graph-x86_64_rtx_4090.json create mode 100644 results/apriltag_ros_apriltag_node-agx_orin.json create mode 100644 results/apriltag_ros_apriltag_node-agx_xavier.json create mode 100644 results/apriltag_ros_apriltag_node-orin_nx.json create mode 100644 results/apriltag_ros_apriltag_node-x86_64_rtx_3060Ti.json create mode 100644 results/apriltag_ros_apriltag_node-x86_64_rtx_4090.json create mode 100644 results/image_proc_rectify_node-agx_orin.json create mode 100644 results/image_proc_rectify_node-agx_xavier.json create mode 100644 results/image_proc_rectify_node-orin_nx.json create mode 100644 results/image_proc_rectify_node-x86_64_rtx_3060Ti.json create mode 100644 results/image_proc_rectify_node-x86_64_rtx_4090.json create mode 100644 results/image_transport_h264_decoder_node-agx_orin.json create mode 100644 results/image_transport_h264_decoder_node-agx_xavier.json create mode 100644 results/image_transport_h264_decoder_node-orin_nx.json create mode 100644 results/image_transport_h264_decoder_node-x86_64_rtx_3060Ti.json create mode 100644 results/image_transport_h264_decoder_node-x86_64_rtx_4090.json create mode 100644 results/image_transport_h264_encoder_node-agx_orin.json create mode 100644 results/image_transport_h264_encoder_node-agx_xavier.json create mode 100644 results/image_transport_h264_encoder_node-orin_nx.json create mode 100644 results/image_transport_h264_encoder_node-x86_64_rtx_3060Ti.json create mode 100644 results/image_transport_h264_encoder_node-x86_64_rtx_4090.json create mode 100644 results/stereo_image_proc_graph-agx_orin.json create mode 100644 results/stereo_image_proc_graph-agx_xavier.json create mode 100644 results/stereo_image_proc_graph-orin_nano_8gb.json create mode 100644 results/stereo_image_proc_graph-orin_nano_emul.json create mode 100644 results/stereo_image_proc_graph-orin_nx.json create mode 100644 results/stereo_image_proc_graph-x86_64_rtx_3060Ti.json create mode 100644 results/stereo_image_proc_graph-x86_64_rtx_4090.json create mode 100644 results/stereo_image_proc_node-agx_orin.json create mode 100644 results/stereo_image_proc_node-agx_xavier.json create mode 100644 results/stereo_image_proc_node-orin_nano_8gb.json create mode 100644 results/stereo_image_proc_node-orin_nano_emul.json create mode 100644 results/stereo_image_proc_node-orin_nx.json create mode 100644 results/stereo_image_proc_node-x86_64_rtx_3060Ti.json create mode 100644 results/stereo_image_proc_node-x86_64_rtx_4090.json create mode 100644 ros2_benchmark/CMakeLists.txt create mode 100644 ros2_benchmark/include/ros2_benchmark/common.hpp create mode 100644 ros2_benchmark/include/ros2_benchmark/data_loader_node.hpp create mode 100644 ros2_benchmark/include/ros2_benchmark/monitor_node.hpp create mode 100644 ros2_benchmark/include/ros2_benchmark/playback_node.hpp create mode 100644 ros2_benchmark/package.xml create mode 100644 ros2_benchmark/ros2_benchmark/__init__.py create mode 100644 ros2_benchmark/ros2_benchmark/basic_performance_calculator.py create mode 100644 ros2_benchmark/ros2_benchmark/default_ros2_benchmark_config.yaml create mode 100644 ros2_benchmark/ros2_benchmark/ros2_benchmark_config.py create mode 100644 ros2_benchmark/ros2_benchmark/ros2_benchmark_test.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/__init__.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/cpu_profiler.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/image_utility.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/nsys_utility.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/profiler.py create mode 100644 ros2_benchmark/ros2_benchmark/utils/ros2_utility.py create mode 100644 ros2_benchmark/src/data_loader_node.cpp create mode 100644 ros2_benchmark/src/monitor_node.cpp create mode 100644 ros2_benchmark/src/playback_node.cpp create mode 100644 ros2_benchmark/test/data_loader_node_pol.py create mode 100644 ros2_benchmark/test/monitor_node_pol.py create mode 100644 ros2_benchmark/test/playback_node_pol.py create mode 100644 ros2_benchmark/test/pol.bag/metadata.yaml create mode 100644 ros2_benchmark/test/pol.bag/pol.bag_0.db3 create mode 100644 ros2_benchmark/test/pol.bag/pol.bag_0.db3.zstd create mode 100644 ros2_benchmark_interfaces/CMakeLists.txt create mode 100644 ros2_benchmark_interfaces/msg/TimestampedMessageArray.msg create mode 100644 ros2_benchmark_interfaces/msg/TopicMessageCount.msg create mode 100644 ros2_benchmark_interfaces/msg/TopicMessageTimestampArray.msg create mode 100644 ros2_benchmark_interfaces/package.xml create mode 100644 ros2_benchmark_interfaces/srv/GetTopicMessageTimestamps.srv create mode 100644 ros2_benchmark_interfaces/srv/PlayMessages.srv create mode 100644 ros2_benchmark_interfaces/srv/SetData.srv create mode 100644 ros2_benchmark_interfaces/srv/StartLoading.srv create mode 100644 ros2_benchmark_interfaces/srv/StartMonitoring.srv create mode 100644 ros2_benchmark_interfaces/srv/StartRecording.srv create mode 100644 ros2_benchmark_interfaces/srv/StopLoading.srv create mode 100644 ros2_benchmark_interfaces/srv/StopRecording.srv create mode 100644 scripts/apriltag_ros_apriltag_graph.py create mode 100644 scripts/apriltag_ros_apriltag_node.py create mode 100644 scripts/image_proc_rectify_node.py create mode 100644 scripts/image_transport_h264_decoder_node.py create mode 100644 scripts/image_transport_h264_encoder_node.py create mode 100644 scripts/stereo_image_proc_graph.py create mode 100644 scripts/stereo_image_proc_node.py diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 0000000..08a3c01 --- /dev/null +++ b/.gitattributes @@ -0,0 +1,24 @@ +# Images +*.gif filter=lfs diff=lfs merge=lfs -text +*.jpg filter=lfs diff=lfs merge=lfs -text +*.png filter=lfs diff=lfs merge=lfs -text +*.psd filter=lfs diff=lfs merge=lfs -text + +# Archives +*.gz filter=lfs diff=lfs merge=lfs -text +*.tar filter=lfs diff=lfs merge=lfs -text +*.zip filter=lfs diff=lfs merge=lfs -text + +# Documents +*.pdf filter=lfs diff=lfs merge=lfs -text + +# Shared libraries +*.so filter=lfs diff=lfs merge=lfs -text +*.so.* filter=lfs diff=lfs merge=lfs -text + +# ROS Bags +**/resources/**/*.db3 filter=lfs diff=lfs merge=lfs -text +**/resources/**/*.yaml filter=lfs diff=lfs merge=lfs -text +ros2_benchmark/test/pol.bag/pol.bag_0.db3 filter=lfs diff=lfs merge=lfs -text +ros2_benchmark/test/pol.bag/pol.bag_0.db3.zstd filter=lfs diff=lfs merge=lfs -text +ros2_benchmark/test/pol.bag/metadata.yaml filter=lfs diff=lfs merge=lfs -text diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..b793570 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +# Ignore all pycache files +**/__pycache__/** diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 0000000..a89cd42 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,14 @@ +# Isaac ROS Contribution Rules + +Any contribution that you make to this repository will +be under the Apache 2 License, as dictated by that +[license](http://www.apache.org/licenses/LICENSE-2.0.html): + +> **5. Submission of Contributions.** Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. + +Contributors must sign-off each commit by adding a `Signed-off-by: ...` +line to commit messages to certify that they have the right to submit +the code they are contributing to the project according to the +[Developer Certificate of Origin (DCO)](https://developercertificate.org/). + +[//]: # (202201002) diff --git a/LICENSE b/LICENSE index 261eeb9..7a4a3ea 100644 --- a/LICENSE +++ b/LICENSE @@ -1,3 +1,4 @@ + Apache License Version 2.0, January 2004 http://www.apache.org/licenses/ @@ -198,4 +199,4 @@ distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and - limitations under the License. + limitations under the License. \ No newline at end of file diff --git a/README.md b/README.md index 53ebea0..b4f6254 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,381 @@ # ros2_benchmark -Benchmark the performance of your ROS 2 graphs + +
ros2_benchmark introduction
+ +## Overview + +Robots are real-time systems which require complex graphs of heterogeneous computation to perform perception, planning, and control. These graphs of computation need to perform work deterministically and with known latency. The computing platform has a fixed budget for heterogeneous computation (TOPS) and throughput; computation is typically performed on multiple CPUs, GPUs, and additional special purpose, fixed function hardware accelerators. + +`ros2_benchmark` provides the tools for measuring the throughput, latency, and compute utilization of these complex graphs without altering the code under test. The results can be used to make informed design decisions on how best a robotics application can meet its real-time requirements. Results can be used to optimize system performance by tracking results over time against changes in the implementation and can be used in the development of program flow monitors to detect anomalies during operation of the real-time robotics application. + +This tooling allows for realistic assessments of robotics application performance under load including message transport costs in [RCL](https://github.com/ros2/rclcpp) for practical benchmarking indicative of your real-world results. Message transport costs can be measured intra-process or inter-process including DDS overhead with support for [type adaptation](https://ros.org/reps/rep-2007.html). This tooling does not require modification of the graph of nodes under test to measure results, allowing both open source and proprietary solutions to be measured with the same tools in an non-intrusive way. Input for benchmarking is standardized with available rosbag datasets accompanying this package. + +Designed for local developer use or in CI/CD platforms, these tools can be containerized to run on cloud native platforms such as Kubernetes. The tools are commercially hardened over tens of thousands of runs. We use this nightly on 7 hardware platforms using `aarch64` and `x86_64` architectures on multiple graph configurations. + +
ros2_benchmark architecture
+
ros2_benchmark uses the benchmark controller to orchestrate the data loader, playback and monitor nodes to perform benchmark runs, and calculate performance results into a benchmark report. + +
+The data loader node fetches input data from rosbag. Input data is pre-processed using a configurable graph of nodes, and buffered into memory in the playback node which supports a plug-in for type adaptation. The graph benchmarked runs unmodified with input from the playback node controlling the data rate to output received at the monitor node.
+ +
ros2_benchmark flow
+
ros2_benchmark loads data from rosbag(s), performs any data pre-processing using a graph of ros nodes, and buffers the input data for benchmarking. If measuring peak throughput, the auto finder runs the graph under benchmark at multiple publisher rates to find the maximum publisher rate with less than 1% drops through the graph, otherwise it uses the specified fixed publishing rate or the timing from the rosbag. + +
+The graph under benchmark is measured multiple times, with calculated results in a benchmark report.
+ +## Table of Contents + +- [ros2\_benchmark](#ros2_benchmark) + - [Overview](#overview) + - [Table of Contents](#table-of-contents) + - [Latest Update](#latest-update) + - [Supported Platforms](#supported-platforms) + - [Quickstart](#quickstart) + - [Datasets](#datasets) + - [Results](#results) + - [Example Results](#example-results) + - [Explanation of the Results JSON Format](#explanation-of-the-results-json-format) + - [Creating Custom Benchmark](#creating-custom-benchmark) + - [Profiling](#profiling) + - [Updates](#updates) + +## Latest Update + +Update 2023-04-05: Initial Release + +## Supported Platforms + +This package is designed and tested to be compatible aarch64 and x86_64 platforms using ROS 2 Humble. + +| Platform hardware | Platform software | ROS Version | +| ------------------- | --------------------------------------------------- | --------------------------------------------------------- | +| aarch64
x86_64 | [Ubuntu 20.04+](https://releases.ubuntu.com/20.04/) | [ROS 2 Humble](https://docs.ros.org/en/humble/index.html) | + +> **Note**: `ros2_benchmark` has been tested on multiple computing platforms including [Intel NUC Corei7 11th Gen](https://ark.intel.com/content/www/us/en/ark/products/228816/intel-nuc-11-enterprise-edge-compute-nuc11tnhv70l.html) and [Jetson Orin](https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/jetson-orin/). + +## Quickstart + +To use and learn to use `ros2_benchmark`, start by running a sample benchmark. Follow the steps below to start measuring performance of an AprilTag node with `ros2_benchmark`. + +1. Set up your development environment by following the instructions [here](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/dev-env-setup.md). + +2. Clone this repository and an available implementation of Apriltag detection under `~/workspaces/isaac_ros-dev/src`. + + ```bash + cd ~/workspaces/isaac_ros-dev/src && \ + git clone https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark && \ + git clone https://github.com/christianrauch/apriltag_ros.git + ``` + +3. Pull down the `r2b dataset 2023` by following the instructions [here](#datasets). + +4. Launch a development Docker container for convenience using the `run_dev.sh` script: + + ```bash + cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \ + ./scripts/run_dev.sh + ``` + +5. Inside the container, build `ros2_benchmark` and source the workspace: + + ```bash + cd /workspaces/isaac_ros-dev && \ + colcon build --symlink-install --packages-up-to ros2_benchmark apriltag_ros && \ + source install/setup.bash + ``` + +6. (Optional) Run tests to verify complete and correct installation: + + ```bash + colcon test --packages-select ros2_benchmark + ``` + +7. Start the AprilTag benchmark: + + ```bash + launch_test src/ros2_benchmark/scripts/apriltag_ros_apriltag_node_test.py + ``` + +8. Once the benchmark is finished, the final performance measurements are displayed in the terminal. + + Additionally, the final results and benchmark metadata (e.g., system information, benchmark configurations) are also exported as a JSON file. + +## Datasets + +Input data for benchmarking is provided in a rosbag. + +To provide consistency of results, we have provided multiple dataset sequences in rosbag for use with `ros2_benchmark`. These dataset sequences were captured on a robot, using very high precision time synchronization between sensors. Captured sensor data includes [HAWK (2mp RGB stereo camera with IMU)](https://www.leopardimaging.com/li-ar0234cs-stereo-gmsl2-hawk/), [D455](https://www.intelrealsense.com/depth-camera-d455/) and [XT32](https://www.hesaitech.com/product/xt32/). + +These datasets are explicitly **not** provided inside this repository. Instead, visit NGC to download the dataset [here](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023). + +You can also download the dataset with command-line tools as follows by first installing the NGC CLI. + +```bash +wget --content-disposition https://ngc.nvidia.com/downloads/ngccli_linux.zip && unzip ngccli_linux.zip && chmod u+x ngc-cli/ngc +``` + +With the NGC CLI available, you can download the dataset with the following commands: + +```bash +./ngc-cli/ngc registry resource download-version "nvidia/isaac/r2bdataset2023:1" +``` + +Then, move the datasets to their required location: + +```bash +mv r2bdataset2023_v1 assets/datasets/r2b_dataset +``` + +| Sequence | Size | Visual | Contents | Description | +| -------------------------------------------------------------------------------------------------- | ---- | ------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [r2b_lounge](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 3.9G | lounge sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 Mono IR 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Lounge sequence containing couch, table, chairs, and staircase with natural planted background wall. | +| [r2b_storage](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 2.9G | storage sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 IR Mono 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Storage sequence including person, AprilTag, shoe, shelving, boxes, pallets | skids, dollys, robots, boundary floor tape, calibration target, and color checker, with 50% reflective background grey walls. | +| [r2b_hallway](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 1.3G | hallway sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 Mono 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Hallway sequence with walking persons, low to no feature not-perpendicular walls, specular highlights, and reflections. | +| [r2b_datacenter](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 1.7G | datacenter sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 Mono 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Datacenter sequence with tall vertical corridor repetitive low-feature surfaces, little color. | +| [r2b_cafe](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 1.2G | cafe sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 Mono 30fps
Depth 1280x780 IR 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Café sequence including table, chairs, stools, reflective flooring, dark reflective glass walls, specular highlights, low wall features, and vibration from floor surface. | +| [r2b_hope](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 30M | hope sequence | D415 RGB | Image from [HOPE dataset](https://github.com/swtyree/hope-dataset/) for 6-DoF pose estimation from [scene 0005](https://github.com/swtyree/hope-dataset/tree/master/hope-image-preview/scene_0005) | +| [r2b_hideaway](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 1.8G | hideaway sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 IR Mono 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Hideaway sequence including table, chairs, seated and moving persons specular highlights, low wall features, and vibration from floor surface. | +| [r2b_mezzanine](https://registry.ngc.nvidia.com/orgs/nvidia/teams/isaac/resources/r2bdataset2023) | 2.0G | mezzanine sequence | LI HAWK stereo
L+R 1920x1200 RGB 30fps

RealSense D455
L+R 1280x720 IR Mono 30fps
Depth 1280x780 30fps
1280x800 RGB 30fps
Hesai XT32 10Hz
| Mezzanine sequence including staircase, railings, table, chairs, highlights, low wall features, and vibration from floor surface. | + +## Results + +Performance measurements are output to a results JSON file. JSON provides a human-readable format which allows for traceable independently verifiable results and can be conveniently imported into your visualization tool of choice. + +Default measurements include throughput, latency, and jitter. These measurements can be performed for the sample rate from the dataset sequence of the rosbag input, at peak throughput, and for fixed frequencies often to represent a sensor capture rate; for example 10hz for LIDAR or 30fps for camera. + +Included in the log is information on the host system on which results were measured, when they were measured, and the corresponding software version. The input data used, and a hash of the input data file is reported for traceability of results. The input YAML configuration used for the benchmark run is reported allowing results to be independent reproduced with the same configuration. + +> **Note**: We use the naming convention `_node` to represent a graph under test that contains a single node (for example, `stereo_image_proc_node.py`) and `_graph` to represent a graph of multiple nodes (for example, `stereo_image_proc_graph.py`). + +### Example Results + +The following are the performance results measured with `ros2_benchmark` on `aarch64` and `x86_64` platforms, using ROS 2 Humble in March 2023. The table below also contains links to the packages for the nodes used in the benchmark and to the complete results JSON files. + +| Node | Input Size | Intel NUC Corei7 11th Gen | AGX Orin (CPU only) | +| -------------------------------------------------------------------------------------------------------------------------------------------------- | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------- | +| [AprilTag Node](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/apriltag_ros_apriltag_node.py) | 720p | [82.9 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/apriltag_ros_apriltag_node-x86_64_rtx_3060Ti.json)
14 ms | [56.3 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/apriltag_ros_apriltag_node-agx_orin.json)
18 ms | +| [Rectify Node](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/image_proc_rectify_node.py) | 1080p | [189 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_proc_rectify_node-x86_64_rtx_3060Ti.json)
5.0 ms | [182 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_proc_rectify_node-agx_orin.json)
5.8 ms | +| [H.264 Encoder Node
I-frame Support](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/image_transport_h264_decoder_node.py) | 1080p | [56.2 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_transport_h264_decoder_node-x86_64_rtx_3060Ti.json)
32 ms | [28.0 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_transport_h264_decoder_node-agx_orin.json)
37 ms | +| [H.264 Encoder Node
P-frame Support](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/image_transport_h264_encoder_node.py) | 1080p | [42.8 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_transport_h264_encoder_node-x86_64_rtx_3060Ti.json)
33 ms | [10.2 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/image_transport_h264_encoder_node-agx_orin.json)
95 ms | +| [Stereo Disparity Node](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/stereo_image_proc_node.py) | 1080p | [99.5 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/stereo_image_proc_node-x86_64_rtx_3060Ti.json)
10 ms | [68.3 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/stereo_image_proc_node-agx_orin.json)
14 ms | + +| Graph | Input Size | Intel NUC Corei7 11th Gen | AGX Orin (CPU only) | +| ------------------------------------------------------------------------------------------------------------------------- | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------- | +| [AprilTag Graph](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/apriltag_ros_apriltag_graph.py) | 720p | [68.3 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/apriltag_ros_apriltag_graph-x86_64_rtx_3060Ti.json)
22 ms | [56.3 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/apriltag_ros_apriltag_graph-agx_orin.json)
22 ms | +| [Stereo Disparity Graph](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/scripts/stereo_image_proc_graph.py) | 1080p | [81.9 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/stereo_image_proc_graph-x86_64_rtx_3060Ti.json)
28 ms | [65.3 fps](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/results/stereo_image_proc_graph-agx_orin.json)
28 ms | + +> **Note**: All results above are using ROS 2 nodes from open source that run computation on the CPU only. For GPU-accelerated equivalent packages, see [Isaac ROS](https://github.com/NVIDIA-ISAAC-ROS). + +### Explanation of the Results JSON Format + +After a `ros2_benchmark`-based benchmark is complete, the framework will output a detailed log of the results in a JSON format. This section explains that JSON format through the use of an example. + +The first section of the output JSON file presents the results achieved running at the peak throughput, as identified by the harness' auto-tune search process. That peak throughput is logged with the key `MEAN_FRAME_RATE`; in this sample, the corresponding value is about ~6.09fps. This iteration of the test was run for `RECEIVED_DURATION = 4919.10` milliseconds. There were `NUM_MISSED_FRAMES = 20.0` frames dropped somewhere in `rclcpp` transport over the path that originates from the playback node, goes through the graph under test, and terminates in the monitor node. + +```json +{ + "BasicPerformanceMetrics.RECEIVED_DURATION": 4919.0, + "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20338761907538, + "BasicPerformanceMetrics.MEAN_FRAME_RATE": 6.098802584821505, + "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 20.0, + "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50.0, + "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 29.333333333333332, + "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 48.0, + "BasicPerformanceMetrics.MAX_JITTER": 231.0, + "BasicPerformanceMetrics.MIN_JITTER": 0.0, + "BasicPerformanceMetrics.MEAN_JITTER": 106.96428571428571, + "BasicPerformanceMetrics.STD_DEV_JITTER": 54.942484366766024, + "CPUProfilingMetrics.MAX_CPU_UTIL": 7.633333333333334, + "CPUProfilingMetrics.MIN_CPU_UTIL": 0.05555555555555555, + "CPUProfilingMetrics.MEAN_CPU_UTIL": 1.5159932659932658, + "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.4090849674792143, + "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.1425925925925924, +} +``` + +The next section of results measures latency at a fixed input throughput of `10.0fps`, as indicated by the section header. In this case, `MEAN_PLAYBACK_FRAME_RATE = 10.2` fps indicates that the true input throughput achieved during the test was close but not exactly equal to the nominal value. The `MEAN_JITTER = 115` ms and `MAX_JITTER = 251` ms indicate the mean and max jitter, respectively. The value `MEAN_FRAME_RATE = 6.12` fps indicates that the output throughput of the graph was significantly slower than the input throughput; this corroborates the previous section's conclusion that the max sustainable frame rate is about ~6.09fps. This iteration of the test was run for `RECEIVED_DURATION = 4900` ms with `NUM_MISSED_FRAMES = 20` frames dropped somewhere in the `rclcpp` transport process. + +Latency tests are often run at the processing rate for the graph under test. The playback rate can be tied to the sensor input rate; many LIDARs run at 10Hz, while cameras may run at 30fps or 60fps. + +If desired, additional fixed playback rates can be specified to calculate additional latency measurements at multiple processing rates. + +```json +{ + "10.0fps": { + "BasicPerformanceMetrics.RECEIVED_DURATION": 4900, + "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.204081632653061, + "BasicPerformanceMetrics.MEAN_FRAME_RATE": 6.122448979591836, + "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 20, + "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, + "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 23, + "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 23, + "BasicPerformanceMetrics.MAX_JITTER": 251.0, + "BasicPerformanceMetrics.MIN_JITTER": 2.0, + "BasicPerformanceMetrics.MEAN_JITTER": 115.64285714285714, + "BasicPerformanceMetrics.STD_DEV_JITTER": 58.463183949824526, + "CPUProfilingMetrics.MAX_CPU_UTIL": 7.855555555555556, + "CPUProfilingMetrics.MIN_CPU_UTIL": 0.16666666666666666, + "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.264444444444445, + "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.9738969321351676, + "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.805555555555555, + } +} +``` + +Finally, the metadata provided at the end of the JSON file contains system and file information to provide a transparent and reproducible record of how the benchmark results were obtained. `BenchmarkMetadata.CONFIG` contains a copy of the configuration file YAML as a string. This configuration can be used to run a benchmark with identical parameters to those from the results file. + +The name and checksum of the dataset used for the benchmark are also provided, ensuring that the same dataset has been used when comparing or reproducing independent results. + +```json +{ + "metadata": { + "BenchmarkMetadata.NAME": "reference AprilTagNode benchmark", + "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/ros-dev/src/ros2_benchmark/scripts/reference_apriltag_node_test.py", + "BenchmarkMetadata.TEST_DATETIME": "2023-03-15T22:07:43Z", + "BenchmarkMetadata.DEVICE_HOSTNAME": "neuromancer", + "BenchmarkMetadata.DEVICE_ARCH": "x86_64", + "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.102.1-microsoft-standard-WSL2 #1 SMP Wed Mar 2 00:30:59 UTC 2022", + "BenchmarkMetadata.BENCHMARK_MODE": 1, + "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 10.0, + "BenchmarkMetadata.INPUT_DATA_PATH": "assets/r2b_storage/r2b_storage.db3", + "BenchmarkMetadata.INPUT_DATA_HASH": "b7e276d5105397dfb19a6f2c6db7672f", + "BenchmarkMetadata.CONFIG": [copy of input config as stringified YAML] + } +} +``` + +> **Note**: The peak throughput of this sample run was capped at 10fps by the input configuation setting `"BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 10.0`. + +## Creating Custom Benchmark + +Benchmark your own graphs using `ros2_benchmark` framework by creating custom benchmark scripts from the minimum template shown below: + +```python +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +def launch_setup(container_prefix, container_sigterm_timeout): + """Graph setup for benchmarking your custom graph.""" + + # Insert your composable node declarations + + # Required DataLoaderNode + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestCustomGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + # Insert remappings if necessary + ) + + # Insert your custom preprocessor graph if needed + + # Required PlaybackNode + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestCustomGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + # Revise "data_formats" based on your graph + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo' + ], + }], + # Revise "remapping" based on your graph + remappings=[ + ('buffer/input0', 'data_loader_node/image'), + ('input0', 'image'), + ('buffer/input1', 'data_loader_node/camera_info'), + ('input1', 'camera_info') + ] + ) + + # Required MonitorNode + # You can add as many monitor nodes as you need to measure performance + # for multiple topics. + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestCustomGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + # Add "monitor_index" parameter to distinguish between various + # monitor nodes when multiple monitor nodes are used. + 'monitor_data_format': 'apriltag_msgs/msg/AprilTagDetectionArray', + }], + # Revise "remapping" based on your graph + remappings=[ + ('output', 'apriltag_detections') + ] + ) + + # Required composable node container + # Insert your composable nodes in the "composable_node_descriptions" list. + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestCustomGraph.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + playback_node, + monitor_node, + # Insert custom nodes here + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestCustomGraph.generate_test_description_with_nsys(launch_setup) + +class TestCustomGraph(ROS2BenchmarkTest): + """Performance test for your custom graph.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + # Insert your custom benchmark configurations + benchmark_name='Custom Graph Benchmark', + input_data_path='datasets/your_custom_rosbag_directory_path', + publisher_upper_frequency=100.0, + publisher_lower_frequency=10.0, + playback_message_buffer_size=10 + ) + + def test_benchmark(self): + self.run_benchmark() +``` + +Revise the existing or insert your code in the template based on your graph to be measured. + +Follow these steps to ensure that everything in the template is configured correctly: + +1. Insert your custom graph (e.g., composable nodes) in the `launch_setup` method. +2. Revise `remappings` in the data loader node to connect rosbag topics to either your preprocessor graph or a playback node. +3. \[Optional\] Insert your preprocessor graph in the `launch_setup` method if required. +4. Revise `data_formats` and `remappings` in the playback node to connect to the loaded/preprocessed data and your custom graph. +5. Insert your custom nodes declared in step 1 to the composable node container. +6. Revise/add benchmark configurations under `ROS2BenchmarkConfig` declaration based on your custom graph. + +The full benchmark configuration options can be found [here](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark/blob/main/ros2_benchmark/ros2_benchmark/default_ros2_benchmark_config.yaml) in the default `ros2_benchmark` configuration file. + +## Profiling + +When seeking to optimize performance, profiling is often used to gain deep insight into the call stack, and where processing time is spent in functions. [ros2_tracing](https://github.com/ros2/ros2_tracing) provides a tracing instrumentation to better understand performance on a CPU, but lacks information on GPU acceleration. + +[Nsight Systems](https://developer.nvidia.com/nsight-systems) provides tracing instrumentation for CPU, GPU, and other SOC (system-on-chip) hardware accelerators for both `aarch64` and `x86_64` platforms, and is freely available for download. We use this tooling to profile our graphs of computation in ROS, to identify areas of improvement for compute optimization, and improvement of synchronization between heterogenous computing hardware. These tools allow for comparison of before and after to inspect profile differences with the benchmark tooling. + +## Updates + +| Date | Changes | +| ---------- | --------------- | +| 2023-04-05 | Initial release | diff --git a/assets/datasets/.gitignore b/assets/datasets/.gitignore new file mode 100644 index 0000000..d6b7ef3 --- /dev/null +++ b/assets/datasets/.gitignore @@ -0,0 +1,2 @@ +* +!.gitignore diff --git a/assets/models/.gitignore b/assets/models/.gitignore new file mode 100644 index 0000000..d6b7ef3 --- /dev/null +++ b/assets/models/.gitignore @@ -0,0 +1,2 @@ +* +!.gitignore diff --git a/resources/r2b_cafe_sequence.gif b/resources/r2b_cafe_sequence.gif new file mode 100644 index 0000000..18e0854 --- /dev/null +++ b/resources/r2b_cafe_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:74cfc83f9b8454852d34f85aeba612eb72a4d9eaaa6574780eecb3600296e489 +size 2153241 diff --git a/resources/r2b_datacenter_sequence.gif b/resources/r2b_datacenter_sequence.gif new file mode 100644 index 0000000..e445ea7 --- /dev/null +++ b/resources/r2b_datacenter_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:0081529ea66a7f097b62a2162a01e955c0429dd867185bdb60f8464dade8d13b +size 2608456 diff --git a/resources/r2b_hallway_sequence.gif b/resources/r2b_hallway_sequence.gif new file mode 100644 index 0000000..bb4f94b --- /dev/null +++ b/resources/r2b_hallway_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:871147173131fb53ff88c401131a01dde9f63e22de09fec82d5152ea83eb3c34 +size 2010246 diff --git a/resources/r2b_hideaway_sequence.gif b/resources/r2b_hideaway_sequence.gif new file mode 100644 index 0000000..1672f88 --- /dev/null +++ b/resources/r2b_hideaway_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:85a4beb962362c377605829aca4442d37233f8aee54ba28ac14155f654731d17 +size 2156052 diff --git a/resources/r2b_hope_sequence.gif b/resources/r2b_hope_sequence.gif new file mode 100644 index 0000000..9197c38 --- /dev/null +++ b/resources/r2b_hope_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:53b8dd6bee1db7773a3eb63d2635bfca28e6fee82c743ed1a4d3d455c49d0c11 +size 119961 diff --git a/resources/r2b_lounge_sequence.gif b/resources/r2b_lounge_sequence.gif new file mode 100644 index 0000000..8923ddc --- /dev/null +++ b/resources/r2b_lounge_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f89ca9a0e8e602e678f36d34f8f8aaa156059081a5b009912f370b0c48dda1d1 +size 2954152 diff --git a/resources/r2b_mezzanine_sequence.gif b/resources/r2b_mezzanine_sequence.gif new file mode 100644 index 0000000..d7220c8 --- /dev/null +++ b/resources/r2b_mezzanine_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc48d523de48a388ce65170d123c23c23533086d0811fb17af06176828d1b40e +size 2871453 diff --git a/resources/r2b_storage_sequence.gif b/resources/r2b_storage_sequence.gif new file mode 100644 index 0000000..9effd0d --- /dev/null +++ b/resources/r2b_storage_sequence.gif @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8d4e9c05f71132293217355a960ec4d79792fcffd693a37f86f4440a78650f85 +size 2934532 diff --git a/resources/ros2_benchmark_arch.png b/resources/ros2_benchmark_arch.png new file mode 100644 index 0000000..f4ac556 --- /dev/null +++ b/resources/ros2_benchmark_arch.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:bdae3e5286bb3377a95f79ac57aa861c117a5df81d1962cac4be30e0abd6c47e +size 55342 diff --git a/resources/ros2_benchmark_flow.png b/resources/ros2_benchmark_flow.png new file mode 100644 index 0000000..7511caf --- /dev/null +++ b/resources/ros2_benchmark_flow.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc26a37e62e66464a0b16866978d2fd6142d3d41168db931c8cf94fa825b6bf6 +size 63099 diff --git a/resources/ros2_benchmark_intro.png b/resources/ros2_benchmark_intro.png new file mode 100644 index 0000000..f205a67 --- /dev/null +++ b/resources/ros2_benchmark_intro.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5ce34e20aaf6a5e78761c281e3c320d5a46fa89d8d4a09aa5d8e553b4900b80c +size 34423 diff --git a/resources/ros_2_rosbag.png b/resources/ros_2_rosbag.png new file mode 100644 index 0000000..3497081 --- /dev/null +++ b/resources/ros_2_rosbag.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:45de1d0a281f13197aeb17a0881ceaa70625bb79598f966a14671cad3339815b +size 8038 diff --git a/results/apriltag_ros_apriltag_graph-agx_orin.json b/results/apriltag_ros_apriltag_graph-agx_orin.json new file mode 100644 index 0000000..696feaa --- /dev/null +++ b/results/apriltag_ros_apriltag_graph-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4973.809163411458, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 56.293519763104854, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 56.29364691516963, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 280.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.661539713541668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.520670572916668, "BasicPerformanceMetrics.MAX_JITTER": 5.090576171875, "BasicPerformanceMetrics.MIN_JITTER": 0.005615234375, "BasicPerformanceMetrics.MEAN_JITTER": 1.0091262927158273, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.5661209040349534, "CPUProfilingMetrics.MAX_CPU_UTIL": 36.40833333333334, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.4166666666666667, "CPUProfilingMetrics.MEAN_CPU_UTIL": 22.194999999999997, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.682915076352002, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 23.91388888888889, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4899.922119140625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203902673900808, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.204243819444477, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.575439453125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.41162109375, "BasicPerformanceMetrics.MAX_JITTER": 2.58447265625, "BasicPerformanceMetrics.MIN_JITTER": 0.1337890625, "BasicPerformanceMetrics.MEAN_JITTER": 1.1052958170572917, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.6023109287697815, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.8500000000000005, "CPUProfilingMetrics.MIN_CPU_UTIL": 5.375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.043333333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5149811215525826, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 6.8500000000000005}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.563232421875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200734609275045, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.201971258675506, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.620361328125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.4169921875, "BasicPerformanceMetrics.MAX_JITTER": 4.22412109375, "BasicPerformanceMetrics.MIN_JITTER": 0.027099609375, "BasicPerformanceMetrics.MEAN_JITTER": 1.0710911106418919, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.558111741196166, "CPUProfilingMetrics.MAX_CPU_UTIL": 13.883333333333335, "CPUProfilingMetrics.MIN_CPU_UTIL": 11.016666666666666, "CPUProfilingMetrics.MEAN_CPU_UTIL": 12.371666666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.9341603478822881, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 12.625}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTag Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:37:54Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 56.09375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTag Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_graph-agx_xavier.json b/results/apriltag_ros_apriltag_graph-agx_xavier.json new file mode 100644 index 0000000..f09bb46 --- /dev/null +++ b/results/apriltag_ros_apriltag_graph-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.506754557292, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 37.85646957181185, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 36.49659839755778, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 6.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 188.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.607421875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 49.900472005208336, "BasicPerformanceMetrics.MAX_JITTER": 6.442138671875, "BasicPerformanceMetrics.MIN_JITTER": 0.00439453125, "BasicPerformanceMetrics.MEAN_JITTER": 1.216977267795139, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9891846444706426, "CPUProfilingMetrics.MAX_CPU_UTIL": 29.275, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 14.544583333333335, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 12.699829382737507, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 26.92083333333333, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4901.582275390625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203788285941437, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.20078766218717, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 31.6962890625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 33.1376953125, "BasicPerformanceMetrics.MAX_JITTER": 6.69775390625, "BasicPerformanceMetrics.MIN_JITTER": 0.045166015625, "BasicPerformanceMetrics.MEAN_JITTER": 2.6316019694010415, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.457161986967299, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.0375, "CPUProfilingMetrics.MIN_CPU_UTIL": 5.949999999999999, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.6049999999999995, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.7884455541055757, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 11.0375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.3896484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200255119407746, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.209109580594895, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.809326171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 31.353515625, "BasicPerformanceMetrics.MAX_JITTER": 12.767578125, "BasicPerformanceMetrics.MIN_JITTER": 0.048095703125, "BasicPerformanceMetrics.MEAN_JITTER": 2.345127415012669, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.8379051823035286, "CPUProfilingMetrics.MAX_CPU_UTIL": 31.5125, "CPUProfilingMetrics.MIN_CPU_UTIL": 22.2125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 24.745, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.4274407361761927, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 23.887500000000003}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTag Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:46:08Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 37.65625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTag Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_graph-orin_nx.json b/results/apriltag_ros_apriltag_graph-orin_nx.json new file mode 100644 index 0000000..a2375d0 --- /dev/null +++ b/results/apriltag_ros_apriltag_graph-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4972.430826822917, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 52.074666744976504, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 52.08720059361763, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 259.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 25.333170572916668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 23.818359375, "BasicPerformanceMetrics.MAX_JITTER": 6.654541015625, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 0.9902704736138133, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.8276311522807901, "CPUProfilingMetrics.MAX_CPU_UTIL": 36.9375, "CPUProfilingMetrics.MIN_CPU_UTIL": 33.462500000000006, "CPUProfilingMetrics.MEAN_CPU_UTIL": 34.57416666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.0351902017483037, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 35.35833333333333, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4899.86083984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203913858638924, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.20437143712727, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 23.95654296875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 23.73681640625, "BasicPerformanceMetrics.MAX_JITTER": 4.758544921875, "BasicPerformanceMetrics.MIN_JITTER": 0.01025390625, "BasicPerformanceMetrics.MEAN_JITTER": 1.5312906901041667, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.1637593770039205, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.5625, "CPUProfilingMetrics.MIN_CPU_UTIL": 6.300000000000001, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.717500000000001, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.47292969879253716, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 6.3125}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4968.205078125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200874154078136, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.191990395173054, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 23.77783203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 25.2392578125, "BasicPerformanceMetrics.MAX_JITTER": 5.159423828125, "BasicPerformanceMetrics.MIN_JITTER": 0.0107421875, "BasicPerformanceMetrics.MEAN_JITTER": 1.3712570602829393, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.0654320777480555, "CPUProfilingMetrics.MAX_CPU_UTIL": 21.474999999999998, "CPUProfilingMetrics.MIN_CPU_UTIL": 20.2875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 20.76, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.4419700216077994, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 20.725}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTag Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:38:21Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 51.875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTag Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_graph-x86_64_rtx_3060Ti.json b/results/apriltag_ros_apriltag_graph-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..cdf5c86 --- /dev/null +++ b/results/apriltag_ros_apriltag_graph-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4971.258870442708, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 70.51107157531938, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 68.28758892865032, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 11.333333333333334, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 351.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 23.384928385416668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 17.588704427083332, "BasicPerformanceMetrics.MAX_JITTER": 17.716064453125, "BasicPerformanceMetrics.MIN_JITTER": 0.005126953125, "BasicPerformanceMetrics.MEAN_JITTER": 3.12129768782747, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.778092399535001, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.945, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.2, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.129393939393939, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.871038018113185, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.37, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4895.722412109375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203014073981816, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.21299734566792, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 24.467529296875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 19.67724609375, "BasicPerformanceMetrics.MAX_JITTER": 27.980712890625, "BasicPerformanceMetrics.MIN_JITTER": 0.12548828125, "BasicPerformanceMetrics.MEAN_JITTER": 13.935201009114584, "BasicPerformanceMetrics.STD_DEV_JITTER": 8.655868859403062, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.455000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.670000000000001, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.441000000000001, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.6268524547291812, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.640000000000001}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4975.775146484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19921590129367, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.09113981190607, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 1, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 19.96142578125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 12.282958984375, "BasicPerformanceMetrics.MAX_JITTER": 18.91064453125, "BasicPerformanceMetrics.MIN_JITTER": 0.005859375, "BasicPerformanceMetrics.MEAN_JITTER": 4.6704282407407405, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.919311095826127, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.23, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.75909090909091, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.427961165439985, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.575}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4973.922119140625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.198441211907095, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.15728763077545, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.840087890625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 28.618408203125, "BasicPerformanceMetrics.MAX_JITTER": 50.89453125, "BasicPerformanceMetrics.MIN_JITTER": 0.07958984375, "BasicPerformanceMetrics.MEAN_JITTER": 14.454510663006756, "BasicPerformanceMetrics.STD_DEV_JITTER": 11.24524177572293, "CPUProfilingMetrics.MAX_CPU_UTIL": 9.205000000000002, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.34500000000000003, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.501666666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.856419184145695, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.545}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTag Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:36:10Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 70.3125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTag Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_graph-x86_64_rtx_4090.json b/results/apriltag_ros_apriltag_graph-x86_64_rtx_4090.json new file mode 100644 index 0000000..48a4fa6 --- /dev/null +++ b/results/apriltag_ros_apriltag_graph-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4993.696940104167, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 102.38673824158148, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 96.72201983531191, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 27.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 510.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 11.093912760416666, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 23.682942708333332, "BasicPerformanceMetrics.MAX_JITTER": 7.44775390625, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.8939437866210938, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.068149376164518, "CPUProfilingMetrics.MAX_CPU_UTIL": 14.93125, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.1875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.624431818181818, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 6.529344184013596, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.177083333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4923.05126953125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.202802622199982, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.156302923239872, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.650634765625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 33.087646484375, "BasicPerformanceMetrics.MAX_JITTER": 46.2978515625, "BasicPerformanceMetrics.MIN_JITTER": 0.302001953125, "BasicPerformanceMetrics.MEAN_JITTER": 16.638427734375, "BasicPerformanceMetrics.STD_DEV_JITTER": 12.308986953133498, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.0625, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.74375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.27125, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.4384917331033733, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.74375}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4994.420166015625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.1968065221829, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.06703281420746, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.90478515625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.671875, "BasicPerformanceMetrics.MAX_JITTER": 20.758056640625, "BasicPerformanceMetrics.MIN_JITTER": 0.01025390625, "BasicPerformanceMetrics.MEAN_JITTER": 4.975956244756712, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.343603447297051, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.19375, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.1875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.957291666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.51119010396483, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.85625}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4984.275146484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.19869948003089, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.094646782451704, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.612060546875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 27.785888671875, "BasicPerformanceMetrics.MAX_JITTER": 50.579833984375, "BasicPerformanceMetrics.MIN_JITTER": 0.015869140625, "BasicPerformanceMetrics.MEAN_JITTER": 19.100704708614863, "BasicPerformanceMetrics.STD_DEV_JITTER": 12.507807066725656, "CPUProfilingMetrics.MAX_CPU_UTIL": 8.881250000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.063541666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.6308749155329596, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.08125}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTag Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:48:54Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 102.1875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTag Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_node-agx_orin.json b/results/apriltag_ros_apriltag_node-agx_orin.json new file mode 100644 index 0000000..527480f --- /dev/null +++ b/results/apriltag_ros_apriltag_node-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4972.9150390625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 56.29393607520256, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 56.30500379224376, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 280.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.749430338541668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.727132161458332, "BasicPerformanceMetrics.MAX_JITTER": 4.0302734375, "BasicPerformanceMetrics.MIN_JITTER": 0.00048828125, "BasicPerformanceMetrics.MEAN_JITTER": 1.0116089745391188, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9001130124477038, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.416666666666666, "CPUProfilingMetrics.MIN_CPU_UTIL": 9.624999999999998, "CPUProfilingMetrics.MEAN_CPU_UTIL": 10.264444444444445, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5739445973878597, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.424999999999999, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4899.154541015625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203856918409302, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.205842575775266, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.67529296875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.721923828125, "BasicPerformanceMetrics.MAX_JITTER": 6.5224609375, "BasicPerformanceMetrics.MIN_JITTER": 0.08251953125, "BasicPerformanceMetrics.MEAN_JITTER": 1.3714853922526042, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.2762208164791524, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.1666666666666665, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.3366666666666664, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5674651237447695, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.1666666666666665}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.58837890625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20091423633444, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.20790056566064, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.673583984375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.52490234375, "BasicPerformanceMetrics.MAX_JITTER": 3.684326171875, "BasicPerformanceMetrics.MIN_JITTER": 0.050537109375, "BasicPerformanceMetrics.MEAN_JITTER": 1.197273872994088, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9240179603761576, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.574999999999999, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.983333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.356666666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.21261598142086, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.55}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTagNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:09:46Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 56.09375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTagNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_node-agx_xavier.json b/results/apriltag_ros_apriltag_node-agx_xavier.json new file mode 100644 index 0000000..3497969 --- /dev/null +++ b/results/apriltag_ros_apriltag_node-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4987.517822265625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 37.85687528869692, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 35.70665223708915, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 10.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 188.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 28.379231770833332, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 50.309488932291664, "BasicPerformanceMetrics.MAX_JITTER": 8.0478515625, "BasicPerformanceMetrics.MIN_JITTER": 0.002197265625, "BasicPerformanceMetrics.MEAN_JITTER": 1.4701926491477273, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.2288354069392453, "CPUProfilingMetrics.MAX_CPU_UTIL": 21.4375, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.74125, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 7.744736418950775, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 17.395833333333332, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4898.153076171875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203871661800646, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.207929238315522, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.646484375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 25.69873046875, "BasicPerformanceMetrics.MAX_JITTER": 8.3310546875, "BasicPerformanceMetrics.MIN_JITTER": 0.0283203125, "BasicPerformanceMetrics.MEAN_JITTER": 2.345001220703125, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.004978735456671, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.574999999999999, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.9000000000000004, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.6725, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.1693855224005465, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.7375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.076171875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.201093865530616, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.21101687214485, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.63330078125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 26.001953125, "BasicPerformanceMetrics.MAX_JITTER": 8.59765625, "BasicPerformanceMetrics.MIN_JITTER": 0.03564453125, "BasicPerformanceMetrics.MEAN_JITTER": 2.208507640941723, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.5723510630178295, "CPUProfilingMetrics.MAX_CPU_UTIL": 14.4625, "CPUProfilingMetrics.MIN_CPU_UTIL": 11.9875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 13.217500000000001, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.0634143124859656, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 11.9875}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTagNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:53:22Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 37.65625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTagNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_node-orin_nx.json b/results/apriltag_ros_apriltag_node-orin_nx.json new file mode 100644 index 0000000..7da869b --- /dev/null +++ b/results/apriltag_ros_apriltag_node-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4989.111328125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 52.07507744302578, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 51.4401803784458, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 2.3333333333333335, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 259.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 19.655110677083332, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 35.252197265625, "BasicPerformanceMetrics.MAX_JITTER": 2.71533203125, "BasicPerformanceMetrics.MIN_JITTER": 0.00439453125, "BasicPerformanceMetrics.MEAN_JITTER": 0.8428512933686023, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7027841240598968, "CPUProfilingMetrics.MAX_CPU_UTIL": 16.7125, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 8.14375, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 7.231725896043417, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.741666666666665, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4893.1669921875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203843191841868, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.218331007265991, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 25.794189453125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 18.8466796875, "BasicPerformanceMetrics.MAX_JITTER": 5.673583984375, "BasicPerformanceMetrics.MIN_JITTER": 0.00537109375, "BasicPerformanceMetrics.MEAN_JITTER": 1.4343414306640625, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.2428963889751103, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.237500000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.35, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.8525, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3117891916022749, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.975}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.300537109375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200921658986175, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.20965173788348, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 19.71630859375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 18.281005859375, "BasicPerformanceMetrics.MAX_JITTER": 4.723876953125, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 1.3563793285472974, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.1351416093451883, "CPUProfilingMetrics.MAX_CPU_UTIL": 9.95, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.670833333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.3561096856661616, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.9}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTagNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:45:47Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 51.875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTagNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_node-x86_64_rtx_3060Ti.json b/results/apriltag_ros_apriltag_node-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..336ff92 --- /dev/null +++ b/results/apriltag_ros_apriltag_node-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4976.709879557292, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 83.94718116641211, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 82.91041066953973, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 5.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 418.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.570068359375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 11.489013671875, "BasicPerformanceMetrics.MAX_JITTER": 11.79931640625, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 1.357513427734375, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.4817453105367744, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.19, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.15, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.2181818181818183, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.8025477328603237, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 6.368333333333333, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4894.314697265625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203482755566103, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.215934833110383, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.096435546875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 15.12353515625, "BasicPerformanceMetrics.MAX_JITTER": 26.339599609375, "BasicPerformanceMetrics.MIN_JITTER": 0.052001953125, "BasicPerformanceMetrics.MEAN_JITTER": 9.435445149739584, "BasicPerformanceMetrics.STD_DEV_JITTER": 7.941061721672677, "CPUProfilingMetrics.MAX_CPU_UTIL": 2.465, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.2, "CPUProfilingMetrics.MEAN_CPU_UTIL": 1.685, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.4513756750202651, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 1.85}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.61865234375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.199776249659756, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.1972223253705, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.4892578125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 14.70068359375, "BasicPerformanceMetrics.MAX_JITTER": 20.553955078125, "BasicPerformanceMetrics.MIN_JITTER": 0.0068359375, "BasicPerformanceMetrics.MEAN_JITTER": 4.296779965394295, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.007593151396193, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.18, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.3, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.034166666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.2777924214136747, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.529999999999999}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4978.76708984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.1987929919926, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.127940771920603, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 13.99853515625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 25.6796875, "BasicPerformanceMetrics.MAX_JITTER": 26.107177734375, "BasicPerformanceMetrics.MIN_JITTER": 0.012451171875, "BasicPerformanceMetrics.MEAN_JITTER": 7.787990260768581, "BasicPerformanceMetrics.STD_DEV_JITTER": 6.257325678135366, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.2700000000000005, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.545, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.4608333333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.721838689373143, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.4}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTagNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:50:29Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 83.75, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTagNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/apriltag_ros_apriltag_node-x86_64_rtx_4090.json b/results/apriltag_ros_apriltag_node-x86_64_rtx_4090.json new file mode 100644 index 0000000..1edd7de --- /dev/null +++ b/results/apriltag_ros_apriltag_node-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4989.017659505208, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 102.38682857097332, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 99.55185369023422, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 13.333333333333334, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 510.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.168538411458334, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 20.14404296875, "BasicPerformanceMetrics.MAX_JITTER": 7.8857421875, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.7341056034482759, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.8879469672790238, "CPUProfilingMetrics.MAX_CPU_UTIL": 8.9875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.0625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.020075757575757, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.7881164978261403, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.966666666666666, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4920.376953125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.202855992616081, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.161823062813164, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.118896484375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 29.9072265625, "BasicPerformanceMetrics.MAX_JITTER": 36.933349609375, "BasicPerformanceMetrics.MIN_JITTER": 0.187744140625, "BasicPerformanceMetrics.MEAN_JITTER": 13.511072794596354, "BasicPerformanceMetrics.STD_DEV_JITTER": 10.74949430281793, "CPUProfilingMetrics.MAX_CPU_UTIL": 2.9625, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.70625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.3775000000000004, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.4010065460812329, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 1.70625}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4987.548583984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19791534344826, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.14979001173773, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.06591796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 14.05322265625, "BasicPerformanceMetrics.MAX_JITTER": 19.60400390625, "BasicPerformanceMetrics.MIN_JITTER": 0.012939453125, "BasicPerformanceMetrics.MEAN_JITTER": 4.334905227558725, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.805935867079221, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.26875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.4375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.611458333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.9432623204756878, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.09375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4985.48388671875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.1991195462425, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.087350276990687, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.11181640625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 28.5634765625, "BasicPerformanceMetrics.MAX_JITTER": 44.39013671875, "BasicPerformanceMetrics.MIN_JITTER": 0.0244140625, "BasicPerformanceMetrics.MEAN_JITTER": 18.522754566089528, "BasicPerformanceMetrics.STD_DEV_JITTER": 12.677575741769282, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.7250000000000005, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.8093749999999997, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.3933470549812779, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.55625}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "apriltag_ros AprilTagNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/apriltag_ros_apriltag_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:26:07Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 102.1875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.INPUT_DATA_START_TIME": 3.0, "BenchmarkMetadata.INPUT_DATA_END_TIME": 3.5, "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: apriltag_ros AprilTagNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: 3.5\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: 3.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 10\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 600.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_proc_rectify_node-agx_orin.json b/results/image_proc_rectify_node-agx_orin.json new file mode 100644 index 0000000..703269c --- /dev/null +++ b/results/image_proc_rectify_node-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4997.042154947917, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 185.25400548960957, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 182.19262943469187, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 14.333333333333334, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 925.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 5.988118489583333, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 9.530110677083334, "BasicPerformanceMetrics.MAX_JITTER": 6.496337890625, "BasicPerformanceMetrics.MIN_JITTER": 0.0, "BasicPerformanceMetrics.MEAN_JITTER": 0.266068279611617, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.38272721588598085, "CPUProfilingMetrics.MAX_CPU_UTIL": 51.26666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.16666666666666666, "CPUProfilingMetrics.MEAN_CPU_UTIL": 24.40530303030303, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 24.639560130970093, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 50.297222222222224, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.088623046875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203758799683225, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.203897081540946, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 5.83642578125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 5.77001953125, "BasicPerformanceMetrics.MAX_JITTER": 1.026123046875, "BasicPerformanceMetrics.MIN_JITTER": 0.02197265625, "BasicPerformanceMetrics.MEAN_JITTER": 0.291168212890625, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.25268249817021077, "CPUProfilingMetrics.MAX_CPU_UTIL": 2.9499999999999997, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.3416666666666668, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.158333333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.527467745196066, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.0}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.658935546875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.20001808744033, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.19673574774433, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 5.556884765625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 5.82861328125, "BasicPerformanceMetrics.MAX_JITTER": 1.461669921875, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 0.27171213034815433, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.2175841037134863, "CPUProfilingMetrics.MAX_CPU_UTIL": 16.2, "CPUProfilingMetrics.MIN_CPU_UTIL": 15.566666666666668, "CPUProfilingMetrics.MEAN_CPU_UTIL": 15.84333333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.23276120333461425, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 16.016666666666666}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.643798828125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200841494540548, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.20148133743603, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 5.762451171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 5.6572265625, "BasicPerformanceMetrics.MAX_JITTER": 1.345703125, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.2915517446157095, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.23871500335189133, "CPUProfilingMetrics.MAX_CPU_UTIL": 9.625, "CPUProfilingMetrics.MIN_CPU_UTIL": 8.858333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.205, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.24679050945195527, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.858333333333333}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "image_proc::RectifyNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_proc_rectify_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:55:29Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 185.078125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_proc::RectifyNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 2500.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_proc_rectify_node-agx_xavier.json b/results/image_proc_rectify_node-agx_xavier.json new file mode 100644 index 0000000..176e080 --- /dev/null +++ b/results/image_proc_rectify_node-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5007.840413411458, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 195.00182244364032, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 187.1473331134782, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 37.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 974.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.211507161458333, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 19.1787109375, "BasicPerformanceMetrics.MAX_JITTER": 16.339599609375, "BasicPerformanceMetrics.MIN_JITTER": 0.00048828125, "BasicPerformanceMetrics.MEAN_JITTER": 0.8953767144795016, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.1467821426450948, "CPUProfilingMetrics.MAX_CPU_UTIL": 58.1375, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 28.243106060606063, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 27.682316849118596, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 57.337500000000006, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.391845703125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203759308065544, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.203265692689893, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 5.80078125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.037841796875, "BasicPerformanceMetrics.MAX_JITTER": 12.5732421875, "BasicPerformanceMetrics.MIN_JITTER": 0.0224609375, "BasicPerformanceMetrics.MEAN_JITTER": 1.1947428385416667, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.027210417005194, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.45, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.987500000000001, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.58, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.49343185953077645, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.7125}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.0859375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19949607417275, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.20365768576512, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.045166015625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 5.70068359375, "BasicPerformanceMetrics.MAX_JITTER": 5.585693359375, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.5806663564387584, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.6790004000871129, "CPUProfilingMetrics.MAX_CPU_UTIL": 19.25, "CPUProfilingMetrics.MIN_CPU_UTIL": 18.275, "CPUProfilingMetrics.MEAN_CPU_UTIL": 18.557499999999997, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3580851853958777, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 18.4375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.3837890625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200649992309746, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.209145228695622, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.867919921875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 5.47119140625, "BasicPerformanceMetrics.MAX_JITTER": 7.58837890625, "BasicPerformanceMetrics.MIN_JITTER": 0.001220703125, "BasicPerformanceMetrics.MEAN_JITTER": 0.933349609375, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9787423457229263, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.05, "CPUProfilingMetrics.MIN_CPU_UTIL": 8.875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.932500000000001, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.7735712636855127, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 9.7375}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "image_proc::RectifyNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_proc_rectify_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T08:03:35Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 194.8046875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_proc::RectifyNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 2500.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_proc_rectify_node-orin_nx.json b/results/image_proc_rectify_node-orin_nx.json new file mode 100644 index 0000000..297bfa1 --- /dev/null +++ b/results/image_proc_rectify_node-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4999.922119140625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 165.82192987447544, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 162.00254677885147, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 18.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 828.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 7.152587890625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 13.376302083333334, "BasicPerformanceMetrics.MAX_JITTER": 4.991943359375, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.8234838958398194, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.587584010462973, "CPUProfilingMetrics.MAX_CPU_UTIL": 68.3875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 31.03068181818182, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 32.91807187059966, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 66.64999999999999, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.115966796875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203750157191562, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.203840141498565, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.29833984375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.255126953125, "BasicPerformanceMetrics.MAX_JITTER": 2.39404296875, "BasicPerformanceMetrics.MIN_JITTER": 0.0029296875, "BasicPerformanceMetrics.MEAN_JITTER": 0.384368896484375, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.42777845839207435, "CPUProfilingMetrics.MAX_CPU_UTIL": 12.725, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.8375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.15, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.3567748658496592, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.7375}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4981.4970703125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.199251291408174, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.222859868344834, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 8.033203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.07958984375, "BasicPerformanceMetrics.MAX_JITTER": 3.410400390625, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 0.3660872286598154, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.5891074664846498, "CPUProfilingMetrics.MAX_CPU_UTIL": 25.55, "CPUProfilingMetrics.MIN_CPU_UTIL": 23.3875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 24.2375, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.7505831066577505, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 23.3875}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.49365234375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20075539246186, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.202394385264768, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.347412109375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.077880859375, "BasicPerformanceMetrics.MAX_JITTER": 3.426025390625, "BasicPerformanceMetrics.MIN_JITTER": 0.00244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.34471666490709457, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.5244729554604504, "CPUProfilingMetrics.MAX_CPU_UTIL": 12.8125, "CPUProfilingMetrics.MIN_CPU_UTIL": 11.8875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 12.505, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3781203512110928, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 12.8125}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "image_proc::RectifyNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_proc_rectify_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:52:01Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 165.625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_proc::RectifyNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 2500.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_proc_rectify_node-x86_64_rtx_3060Ti.json b/results/image_proc_rectify_node-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..7668bda --- /dev/null +++ b/results/image_proc_rectify_node-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5011.115559895833, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 194.98777414572444, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 188.91212271610812, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 28.666666666666668, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 974.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 4.271484375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 19.930582682291668, "BasicPerformanceMetrics.MAX_JITTER": 5.3330078125, "BasicPerformanceMetrics.MIN_JITTER": 0.0, "BasicPerformanceMetrics.MEAN_JITTER": 0.7888703208556149, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7807628006922117, "CPUProfilingMetrics.MAX_CPU_UTIL": 29.375, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.15, "CPUProfilingMetrics.MEAN_CPU_UTIL": 13.320454545454547, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 13.833210668788517, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 28.628333333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4904.35693359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.201528505775446, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.195016528570987, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 3.79931640625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.929931640625, "BasicPerformanceMetrics.MAX_JITTER": 5.970703125, "BasicPerformanceMetrics.MIN_JITTER": 0.001220703125, "BasicPerformanceMetrics.MEAN_JITTER": 0.8275705973307291, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.1305080967834902, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.075, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5549999999999999, "CPUProfilingMetrics.MEAN_CPU_UTIL": 1.217, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.9646999533533731, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 0.6}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4987.36572265625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19431182368044, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.151995398528996, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 4.091064453125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.59716796875, "BasicPerformanceMetrics.MAX_JITTER": 6.0703125, "BasicPerformanceMetrics.MIN_JITTER": 0.00439453125, "BasicPerformanceMetrics.MEAN_JITTER": 0.5933387295511745, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.6691427230195265, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.055000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.0, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.031666666666668, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.6022315614383014, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.33}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4968.52490234375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.199073531352553, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.190046935105844, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 4.99658203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 6.481689453125, "BasicPerformanceMetrics.MAX_JITTER": 4.468994140625, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 0.885425464527027, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9054682486884615, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.709999999999999, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.145, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.289166666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.1356621294303255, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.709999999999999}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "image_proc::RectifyNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_proc_rectify_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T08:07:53Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 194.8046875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_proc::RectifyNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 2500.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_proc_rectify_node-x86_64_rtx_4090.json b/results/image_proc_rectify_node-x86_64_rtx_4090.json new file mode 100644 index 0000000..238ac07 --- /dev/null +++ b/results/image_proc_rectify_node-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4997.471110026042, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 622.9545893240639, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 619.7893153610273, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 15.666666666666666, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 3113.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 1.926025390625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 2.243896484375, "BasicPerformanceMetrics.MAX_JITTER": 4.12060546875, "BasicPerformanceMetrics.MIN_JITTER": 0.0, "BasicPerformanceMetrics.MEAN_JITTER": 0.07487857673117324, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.1273964537249417, "CPUProfilingMetrics.MAX_CPU_UTIL": 37.725, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.1875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 16.40189393939394, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 17.343613702454245, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 35.46666666666666, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4906.33984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20316046881131, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.190896185818254, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 1.649169921875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.546630859375, "BasicPerformanceMetrics.MAX_JITTER": 12.384033203125, "BasicPerformanceMetrics.MIN_JITTER": 0.033203125, "BasicPerformanceMetrics.MEAN_JITTER": 2.357365926106771, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.2347003943701536, "CPUProfilingMetrics.MAX_CPU_UTIL": 2.18125, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.38125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 1.75, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.2969111820056631, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 1.38125}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4989.330322265625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19361593994354, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.128309937950114, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 1.743408203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.156494140625, "BasicPerformanceMetrics.MAX_JITTER": 12.400146484375, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 1.112996146182886, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.4357359363470397, "CPUProfilingMetrics.MAX_CPU_UTIL": 15.50625, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.30625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 12.572916666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 5.0610050090262595, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 15.375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4972.648193359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.197828213874153, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.165013523440997, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 1.795166015625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.19873046875, "BasicPerformanceMetrics.MAX_JITTER": 11.675537109375, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.9338840793918919, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.9612979971080644, "CPUProfilingMetrics.MAX_CPU_UTIL": 8.568750000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.925, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.8562545587126276, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.9375}, "custom": {"data_resolution": "HD (1280,720)"}, "metadata": {"BenchmarkMetadata.NAME": "image_proc::RectifyNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_proc_rectify_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T08:29:04Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 622.7734375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_storage", "BenchmarkMetadata.INPUT_DATA_SIZE": 3087908864, "BenchmarkMetadata.INPUT_DATA_HASH": "5e8f11201fe10dbac7307a8628553e94", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_proc::RectifyNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(1280, 720, HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_storage\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 2500.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_decoder_node-agx_orin.json b/results/image_transport_h264_decoder_node-agx_orin.json new file mode 100644 index 0000000..6434d98 --- /dev/null +++ b/results/image_transport_h264_decoder_node-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4961.859375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 28.013350572102258, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 28.01369194603439, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 139.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 36.709147135416664, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 36.64794921875, "BasicPerformanceMetrics.MAX_JITTER": 1.287353515625, "BasicPerformanceMetrics.MIN_JITTER": 0.000732421875, "BasicPerformanceMetrics.MEAN_JITTER": 0.1553482835310219, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.13880038992228247, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.483333333333333, "CPUProfilingMetrics.MIN_CPU_UTIL": 9.0, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.713333333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.41290041103398517, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 9.797222222222222, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.03759765625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203981475986987, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.20400333742656, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 36.585205078125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 36.57470703125, "BasicPerformanceMetrics.MAX_JITTER": 0.557861328125, "BasicPerformanceMetrics.MIN_JITTER": 0.0361328125, "BasicPerformanceMetrics.MEAN_JITTER": 0.16943359375, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.10224226124942692, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.9916666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.0833333333333335, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.4666666666666672, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3279142841929546, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.1666666666666665}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Decoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_decoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:43:05Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 27.8125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Decoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 1\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_decoder_node-agx_xavier.json b/results/image_transport_h264_decoder_node-agx_xavier.json new file mode 100644 index 0000000..6aff6dd --- /dev/null +++ b/results/image_transport_h264_decoder_node-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5324.946126302083, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 28.013612917539636, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 25.600255521379637, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 2.6666666666666665, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 139.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 40.866129557291664, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 404.2188313802083, "BasicPerformanceMetrics.MAX_JITTER": 18.4013671875, "BasicPerformanceMetrics.MIN_JITTER": 0.00048828125, "BasicPerformanceMetrics.MEAN_JITTER": 1.716968677662037, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.652003122561876, "CPUProfilingMetrics.MAX_CPU_UTIL": 18.299999999999997, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.392916666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 6.68498947798687, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.566666666666668, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4898.8330078125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203877762526767, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.206512432708285, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 42.458740234375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 41.19384765625, "BasicPerformanceMetrics.MAX_JITTER": 18.67333984375, "BasicPerformanceMetrics.MIN_JITTER": 0.0517578125, "BasicPerformanceMetrics.MEAN_JITTER": 6.6923065185546875, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.4827866699951295, "CPUProfilingMetrics.MAX_CPU_UTIL": 28.9125, "CPUProfilingMetrics.MIN_CPU_UTIL": 20.9375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 26.3, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.8401584462842915, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 28.9125}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Decoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_decoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:58:38Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 27.8125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Decoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 1\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_decoder_node-orin_nx.json b/results/image_transport_h264_decoder_node-orin_nx.json new file mode 100644 index 0000000..d9d8efe --- /dev/null +++ b/results/image_transport_h264_decoder_node-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5350.896321614583, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 28.01353940505049, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 25.416304196190854, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 3.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 139.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 41.16796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 430.2591959635417, "BasicPerformanceMetrics.MAX_JITTER": 27.55078125, "BasicPerformanceMetrics.MIN_JITTER": 0.000732421875, "BasicPerformanceMetrics.MEAN_JITTER": 0.9848651031949627, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.1572855053914637, "CPUProfilingMetrics.MAX_CPU_UTIL": 15.7625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 8.357083333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 6.34438669177582, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.579166666666666, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4899.8779296875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203866069474776, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.20433584621747, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 41.285888671875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 41.060302734375, "BasicPerformanceMetrics.MAX_JITTER": 0.692138671875, "BasicPerformanceMetrics.MIN_JITTER": 0.003662109375, "BasicPerformanceMetrics.MEAN_JITTER": 0.19063822428385416, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.14379403529647114, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.875, "CPUProfilingMetrics.MIN_CPU_UTIL": 5.6875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.180000000000001, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.4100762124288606, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 6.05}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Decoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_decoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:56:32Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 27.8125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Decoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 1\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_decoder_node-x86_64_rtx_3060Ti.json b/results/image_transport_h264_decoder_node-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..ebcb398 --- /dev/null +++ b/results/image_transport_h264_decoder_node-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5109.133544921875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 57.699960911037884, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 56.17399518962518, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 287.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 28.787516276041668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 161.540771484375, "BasicPerformanceMetrics.MAX_JITTER": 20.9482421875, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 2.089810341282895, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.948571084180937, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.15, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.8550000000000001, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.009722222222223, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.7804298294574687, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.783333333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4911.77734375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203376510521958, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.179614526628043, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 22.5966796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 34.035400390625, "BasicPerformanceMetrics.MAX_JITTER": 43.264892578125, "BasicPerformanceMetrics.MIN_JITTER": 0.0107421875, "BasicPerformanceMetrics.MEAN_JITTER": 9.852930704752604, "BasicPerformanceMetrics.STD_DEV_JITTER": 9.25175065710845, "CPUProfilingMetrics.MAX_CPU_UTIL": 2.76, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.1350000000000002, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.398, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.20903588208726256, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.1350000000000002}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 5141.81689453125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19966712837055, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 56.20581322282704, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 11, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 33.216552734375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 191.6171875, "BasicPerformanceMetrics.MAX_JITTER": 19.51025390625, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 0.8634632921385017, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.0963911605526953, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.235, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.965909090909091, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.530459730223145, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.5}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.0146484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200649992309746, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.211391228665416, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.235595703125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 30.4697265625, "BasicPerformanceMetrics.MAX_JITTER": 22.068359375, "BasicPerformanceMetrics.MIN_JITTER": 0.00390625, "BasicPerformanceMetrics.MEAN_JITTER": 5.522378457559122, "BasicPerformanceMetrics.STD_DEV_JITTER": 6.865368633171297, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.9549999999999996, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.2, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.9475, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.2489287075997038, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.3299999999999996}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Decoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_decoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:29:37Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 57.5, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Decoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 1\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_decoder_node-x86_64_rtx_4090.json b/results/image_transport_h264_decoder_node-x86_64_rtx_4090.json new file mode 100644 index 0000000..6290b47 --- /dev/null +++ b/results/image_transport_h264_decoder_node-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5131.646484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 63.637270486100384, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 61.38651596292636, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 2.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 317.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 20.707926432291668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 170.8720703125, "BasicPerformanceMetrics.MAX_JITTER": 19.678955078125, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 3.6287681896465656, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.8450525100575375, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.8125, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.783712121212121, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.25878704792721, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.235416666666667, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4920.96923828125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20341717822007, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.160599991367459, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.665283203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 38.3154296875, "BasicPerformanceMetrics.MAX_JITTER": 55.732421875, "BasicPerformanceMetrics.MIN_JITTER": 0.062744140625, "BasicPerformanceMetrics.MEAN_JITTER": 15.185638427734375, "BasicPerformanceMetrics.STD_DEV_JITTER": 12.177955389133109, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.43125, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.4625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.85375, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3207072262983795, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.75625}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4972.87060546875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.199555058269084, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.32732878070161, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.3818359375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.826904296875, "BasicPerformanceMetrics.MAX_JITTER": 19.9267578125, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 2.545224183357802, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.1166536070366, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.0687500000000005, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.18125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.878125, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.1091867199922505, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 6.55}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4958.48388671875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.199981980284186, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.25118230227056, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.301025390625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 18.89453125, "BasicPerformanceMetrics.MAX_JITTER": 39.51025390625, "BasicPerformanceMetrics.MIN_JITTER": 0.007568359375, "BasicPerformanceMetrics.MEAN_JITTER": 10.251425253378379, "BasicPerformanceMetrics.STD_DEV_JITTER": 7.571219770365117, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.50625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.68125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.4760416666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.2752420964326299, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.90625}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Decoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_decoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T08:09:47Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 63.4375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Decoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 1\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_encoder_node-agx_orin.json b/results/image_transport_h264_encoder_node-agx_orin.json new file mode 100644 index 0000000..dfa65ae --- /dev/null +++ b/results/image_transport_h264_encoder_node-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.54052734375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.204107223031636, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.202956128502587, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 94.83756510416667, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 95.43050130208333, "BasicPerformanceMetrics.MAX_JITTER": 4.080322265625, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.6007792154947916, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7177242053929165, "CPUProfilingMetrics.MAX_CPU_UTIL": 9.716666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 8.575, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.037222222222221, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.279451061863703, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 9.275, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.288818359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.204067905481034, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.203480213792805, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 94.940673828125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 95.222900390625, "BasicPerformanceMetrics.MAX_JITTER": 3.9873046875, "BasicPerformanceMetrics.MIN_JITTER": 0.00341796875, "BasicPerformanceMetrics.MEAN_JITTER": 0.830780029296875, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.0827708931115496, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.641666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 8.741666666666667, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.225, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.7138316016789644, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.641666666666667}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Encoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_encoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:45:56Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 10.0, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Encoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_encoder_node-agx_xavier.json b/results/image_transport_h264_encoder_node-agx_xavier.json new file mode 100644 index 0000000..8654d29 --- /dev/null +++ b/results/image_transport_h264_encoder_node-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 6106.023844401042, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.204219585548953, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 8.024890421150639, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 1.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 126.83846028645833, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 1335.7207845052083, "BasicPerformanceMetrics.MAX_JITTER": 3.907470703125, "BasicPerformanceMetrics.MIN_JITTER": 0.017578125, "BasicPerformanceMetrics.MEAN_JITTER": 0.9098030252659575, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7893925137848957, "CPUProfilingMetrics.MAX_CPU_UTIL": 18.4625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.8625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 10.320416666666668, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 6.247044157051788, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.695833333333335, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 6070.7041015625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203591036284775, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 8.071551368709965, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 1, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 125.775634765625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 1296.244140625, "BasicPerformanceMetrics.MAX_JITTER": 3.175048828125, "BasicPerformanceMetrics.MIN_JITTER": 0.0048828125, "BasicPerformanceMetrics.MEAN_JITTER": 0.6378199800531915, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.5712135085945212, "CPUProfilingMetrics.MAX_CPU_UTIL": 16.275, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 10.4875, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 5.799814113400531, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.125}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Encoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_encoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:20:16Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 10.0, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Encoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_encoder_node-orin_nx.json b/results/image_transport_h264_encoder_node-orin_nx.json new file mode 100644 index 0000000..935dcbf --- /dev/null +++ b/results/image_transport_h264_encoder_node-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5187.732340494792, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20397995107745, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 9.63812292898726, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 105.16715494791667, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 395.201171875, "BasicPerformanceMetrics.MAX_JITTER": 3.381103515625, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.3447011311848958, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.4725793546308892, "CPUProfilingMetrics.MAX_CPU_UTIL": 15.7, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 12.582638888888889, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.6925163890452737, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.8125, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 5187.46533203125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.204014013977606, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 9.638618631581593, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 113.7099609375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 401.142822265625, "BasicPerformanceMetrics.MAX_JITTER": 3.289794921875, "BasicPerformanceMetrics.MIN_JITTER": 0.001708984375, "BasicPerformanceMetrics.MEAN_JITTER": 0.2697499593098958, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.4769606991383969, "CPUProfilingMetrics.MAX_CPU_UTIL": 14.7375, "CPUProfilingMetrics.MIN_CPU_UTIL": 4.2125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 12.487500000000002, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.720607029325546, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.7375}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Encoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_encoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:34:39Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 10.0, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Encoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_encoder_node-x86_64_rtx_3060Ti.json b/results/image_transport_h264_encoder_node-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..c9a627f --- /dev/null +++ b/results/image_transport_h264_encoder_node-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 5189.708821614583, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 45.83771520744373, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 42.84483587056045, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 5.666666666666667, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 228.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.133951822916668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 243.170166015625, "BasicPerformanceMetrics.MAX_JITTER": 2.212646484375, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.2445889559659091, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.28249941727011557, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.2, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.3, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.1566666666666663, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.4648934629822308, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.901666666666666, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4901.30224609375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.200061150561917, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.201370470439587, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 36.012451171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 35.38330078125, "BasicPerformanceMetrics.MAX_JITTER": 19.814208984375, "BasicPerformanceMetrics.MIN_JITTER": 0.044189453125, "BasicPerformanceMetrics.MEAN_JITTER": 3.3298441569010415, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.547187130538502, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.2399999999999998, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.1, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.674, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.44143402678089944, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.41}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4967.01171875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20314268025559, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.199244232455534, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.62939453125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 33.2705078125, "BasicPerformanceMetrics.MAX_JITTER": 30.052001953125, "BasicPerformanceMetrics.MIN_JITTER": 0.004150390625, "BasicPerformanceMetrics.MEAN_JITTER": 5.245976628483953, "BasicPerformanceMetrics.STD_DEV_JITTER": 7.672662837291412, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.840000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.814166666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.4944798890881366, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.42}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Encoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_encoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:43:51Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 45.625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Encoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/image_transport_h264_encoder_node-x86_64_rtx_4090.json b/results/image_transport_h264_encoder_node-x86_64_rtx_4090.json new file mode 100644 index 0000000..197ea3b --- /dev/null +++ b/results/image_transport_h264_encoder_node-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4980.859537760417, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 45.825723764859504, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 45.77523670396113, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 228.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.883951822916668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 30.076416015625, "BasicPerformanceMetrics.MAX_JITTER": 12.456298828125, "BasicPerformanceMetrics.MIN_JITTER": 0.00048828125, "BasicPerformanceMetrics.MEAN_JITTER": 0.7236392941095132, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.8608992360266476, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.9625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 6.105902777777778, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.4059181065526425, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.283333333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4919.017578125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.194593788993512, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.164631291896844, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 22.35205078125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 36.809326171875, "BasicPerformanceMetrics.MAX_JITTER": 45.195068359375, "BasicPerformanceMetrics.MIN_JITTER": 0.013427734375, "BasicPerformanceMetrics.MEAN_JITTER": 10.969579060872396, "BasicPerformanceMetrics.STD_DEV_JITTER": 9.370220091225004, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.2499999999999996, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.78125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.03875, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.18512664584008418, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.1312499999999996}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4971.34326171875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.201081989154154, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.172931560581933, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 22.38525390625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 27.01904296875, "BasicPerformanceMetrics.MAX_JITTER": 31.08642578125, "BasicPerformanceMetrics.MIN_JITTER": 0.006103515625, "BasicPerformanceMetrics.MEAN_JITTER": 12.097624907622466, "BasicPerformanceMetrics.STD_DEV_JITTER": 9.006736775205109, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.29375, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.05625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.242708333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.4446805112251944, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.825}, "metadata": {"BenchmarkMetadata.NAME": "image_transport H264 Encoder Node Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/image_transport_h264_encoder_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T09:41:27Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 45.625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_mezzanine", "BenchmarkMetadata.INPUT_DATA_SIZE": 2057437184, "BenchmarkMetadata.INPUT_DATA_HASH": "c84d7420c5524d882f1019d350232fb1", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: image_transport H264 Encoder Node Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info: {}\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_mezzanine\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 200.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-agx_orin.json b/results/stereo_image_proc_graph-agx_orin.json new file mode 100644 index 0000000..45e1554 --- /dev/null +++ b/results/stereo_image_proc_graph-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4987.947998046875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 66.45031240060383, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 65.28126702338751, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 5.333333333333333, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 331.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 31.7421875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 38.099934895833336, "BasicPerformanceMetrics.MAX_JITTER": 18.35400390625, "BasicPerformanceMetrics.MIN_JITTER": 0.002197265625, "BasicPerformanceMetrics.MEAN_JITTER": 2.2629984096845974, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.444432057295717, "CPUProfilingMetrics.MAX_CPU_UTIL": 36.425, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.08333333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 18.023055555555555, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 17.287569065409162, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 35.86944444444444, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4898.489501953125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203860477155036, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.207228162898788, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.3955078125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 30.77880859375, "BasicPerformanceMetrics.MAX_JITTER": 6.156494140625, "BasicPerformanceMetrics.MIN_JITTER": 0.0087890625, "BasicPerformanceMetrics.MEAN_JITTER": 1.7597249348958333, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.4986082915245784, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.75, "CPUProfilingMetrics.MIN_CPU_UTIL": 5.1, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.5600000000000005, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.24183327590167042, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.741666666666667}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.325927734375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.20103264759614, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.20075835906489, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 29.919677734375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 29.9423828125, "BasicPerformanceMetrics.MAX_JITTER": 7.755615234375, "BasicPerformanceMetrics.MIN_JITTER": 0.0048828125, "BasicPerformanceMetrics.MEAN_JITTER": 1.00314515389052, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.237528527451365, "CPUProfilingMetrics.MAX_CPU_UTIL": 33.108333333333334, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.0, "CPUProfilingMetrics.MEAN_CPU_UTIL": 27.541666666666668, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 11.871249895191074, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 32.8}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.794677734375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20097807125858, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.200563891322993, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 28.47607421875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 28.544189453125, "BasicPerformanceMetrics.MAX_JITTER": 15.487548828125, "BasicPerformanceMetrics.MIN_JITTER": 0.000732421875, "BasicPerformanceMetrics.MEAN_JITTER": 2.0992118216849662, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.4768166252355255, "CPUProfilingMetrics.MAX_CPU_UTIL": 17.091666666666665, "CPUProfilingMetrics.MIN_CPU_UTIL": 15.066666666666668, "CPUProfilingMetrics.MEAN_CPU_UTIL": 15.903333333333336, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.7272780302836959, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 15.066666666666668}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:36:00Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 66.25, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-agx_xavier.json b/results/stereo_image_proc_graph-agx_xavier.json new file mode 100644 index 0000000..c110105 --- /dev/null +++ b/results/stereo_image_proc_graph-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4956.579264322917, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 32.70099928625164, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 31.943198920387434, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 3.6666666666666665, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 162.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 48.087158203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 49.688151041666664, "BasicPerformanceMetrics.MAX_JITTER": 59.0703125, "BasicPerformanceMetrics.MIN_JITTER": 0.0224609375, "BasicPerformanceMetrics.MEAN_JITTER": 11.59314878295068, "BasicPerformanceMetrics.STD_DEV_JITTER": 8.371916045617235, "CPUProfilingMetrics.MAX_CPU_UTIL": 40.625, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 31.241237373737373, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 10.72546765468391, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 37.55416666666667, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4891.038818359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203876745738574, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.222777176152476, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 65.49560546875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 56.43603515625, "BasicPerformanceMetrics.MAX_JITTER": 33.1298828125, "BasicPerformanceMetrics.MIN_JITTER": 0.025634765625, "BasicPerformanceMetrics.MEAN_JITTER": 5.3473052978515625, "BasicPerformanceMetrics.STD_DEV_JITTER": 6.38256175711429, "CPUProfilingMetrics.MAX_CPU_UTIL": 12.774999999999999, "CPUProfilingMetrics.MIN_CPU_UTIL": 10.325, "CPUProfilingMetrics.MEAN_CPU_UTIL": 11.709999999999999, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.8485060400492149, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 12.774999999999999}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4956.884521484375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20190445029781, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.26094300762153, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 58.128173828125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 48.4384765625, "BasicPerformanceMetrics.MAX_JITTER": 39.083740234375, "BasicPerformanceMetrics.MIN_JITTER": 0.056884765625, "BasicPerformanceMetrics.MEAN_JITTER": 9.348934689083615, "BasicPerformanceMetrics.STD_DEV_JITTER": 7.642007046497729, "CPUProfilingMetrics.MAX_CPU_UTIL": 36.8, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.1375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 29.8125, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 11.960725660817296, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 35.262499999999996}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T08:04:28Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 32.5, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-orin_nano_8gb.json b/results/stereo_image_proc_graph-orin_nano_8gb.json new file mode 100644 index 0000000..ec1115e --- /dev/null +++ b/results/stereo_image_proc_graph-orin_nano_8gb.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4986.545654296875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 43.951920854367245, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 41.88975797829232, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 9.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 218.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 48.64892578125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 74.13175455729167, "BasicPerformanceMetrics.MAX_JITTER": 40.704833984375, "BasicPerformanceMetrics.MIN_JITTER": 0.012451171875, "BasicPerformanceMetrics.MEAN_JITTER": 7.495113732679835, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.7573273960511235, "CPUProfilingMetrics.MAX_CPU_UTIL": 69.11666666666666, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5, "CPUProfilingMetrics.MEAN_CPU_UTIL": 32.68924242424242, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 32.81729640885564, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 67.5, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4896.319580078125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203413619783543, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.211751741744399, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 49.86865234375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 45.867431640625, "BasicPerformanceMetrics.MAX_JITTER": 25.044189453125, "BasicPerformanceMetrics.MIN_JITTER": 0.16943359375, "BasicPerformanceMetrics.MEAN_JITTER": 6.1652272542317705, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.80619579609136, "CPUProfilingMetrics.MAX_CPU_UTIL": 17.733333333333334, "CPUProfilingMetrics.MIN_CPU_UTIL": 16.166666666666668, "CPUProfilingMetrics.MEAN_CPU_UTIL": 16.87666666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5450382249591917, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 17.733333333333334}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4959.33642578125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.202156839053274, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.245981946338784, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 46.86767578125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 39.67138671875, "BasicPerformanceMetrics.MAX_JITTER": 23.93896484375, "BasicPerformanceMetrics.MIN_JITTER": 0.034912109375, "BasicPerformanceMetrics.MEAN_JITTER": 6.891385465054898, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.603279088187622, "CPUProfilingMetrics.MAX_CPU_UTIL": 49.23333333333333, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.3333333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 39.86944444444445, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 17.259212292298198, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 46.03333333333334}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:36:23Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 43.75, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-orin_nano_emul.json b/results/stereo_image_proc_graph-orin_nano_emul.json new file mode 100644 index 0000000..002bb6e --- /dev/null +++ b/results/stereo_image_proc_graph-orin_nano_emul.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.126627604167, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 43.95147590557565, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 43.533883484769795, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 1.6666666666666667, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 218.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 44.717854817708336, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 48.959635416666664, "BasicPerformanceMetrics.MAX_JITTER": 34.80224609375, "BasicPerformanceMetrics.MIN_JITTER": 0.0224609375, "BasicPerformanceMetrics.MEAN_JITTER": 6.683962799781977, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.487434674592412, "CPUProfilingMetrics.MAX_CPU_UTIL": 67.7, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5, "CPUProfilingMetrics.MEAN_CPU_UTIL": 32.23934343434343, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 31.829008236484572, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 66.02777777777779, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4909.550537109375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20344513745057, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.184231656659714, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 40.873291015625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 50.1181640625, "BasicPerformanceMetrics.MAX_JITTER": 15.312255859375, "BasicPerformanceMetrics.MIN_JITTER": 0.264892578125, "BasicPerformanceMetrics.MEAN_JITTER": 5.515096028645833, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.9929398645581786, "CPUProfilingMetrics.MAX_CPU_UTIL": 19.5, "CPUProfilingMetrics.MIN_CPU_UTIL": 15.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 16.96, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.572068700788868, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 19.5}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4975.373779296875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.201114649211892, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.14848866715661, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 46.99951171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 55.669189453125, "BasicPerformanceMetrics.MAX_JITTER": 27.299072265625, "BasicPerformanceMetrics.MIN_JITTER": 0.12548828125, "BasicPerformanceMetrics.MEAN_JITTER": 7.085742847339527, "BasicPerformanceMetrics.STD_DEV_JITTER": 6.186234496876942, "CPUProfilingMetrics.MAX_CPU_UTIL": 73.11666666666666, "CPUProfilingMetrics.MIN_CPU_UTIL": 27.733333333333334, "CPUProfilingMetrics.MEAN_CPU_UTIL": 53.83611111111111, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 15.68553065451023, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 47.76666666666667}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:49:49Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 43.75, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-orin_nx.json b/results/stereo_image_proc_graph-orin_nx.json new file mode 100644 index 0000000..f9004cc --- /dev/null +++ b/results/stereo_image_proc_graph-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4982.283121744792, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 55.19969189335796, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 55.195580688241535, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 275.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.4052734375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 32.895833333333336, "BasicPerformanceMetrics.MAX_JITTER": 9.8740234375, "BasicPerformanceMetrics.MIN_JITTER": 0.00537109375, "BasicPerformanceMetrics.MEAN_JITTER": 2.0721618875915753, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.9222912010954236, "CPUProfilingMetrics.MAX_CPU_UTIL": 50.625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 41.004861111111104, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 17.844913231936108, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 48.291666666666664, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4898.4765625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203687118283453, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.207255125557213, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 33.64306640625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 31.93017578125, "BasicPerformanceMetrics.MAX_JITTER": 6.8994140625, "BasicPerformanceMetrics.MIN_JITTER": 0.021240234375, "BasicPerformanceMetrics.MEAN_JITTER": 2.086644490559896, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.577542816266887, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.337499999999999, "CPUProfilingMetrics.MIN_CPU_UTIL": 8.774999999999999, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.452499999999999, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5044427618669931, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 9.4625}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.954833984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20095134962959, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.199590093649693, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 32.701171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 32.925048828125, "BasicPerformanceMetrics.MAX_JITTER": 10.031005859375, "BasicPerformanceMetrics.MIN_JITTER": 0.00634765625, "BasicPerformanceMetrics.MEAN_JITTER": 2.4393673458614864, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.112866666992609, "CPUProfilingMetrics.MAX_CPU_UTIL": 28.424999999999997, "CPUProfilingMetrics.MIN_CPU_UTIL": 26.425, "CPUProfilingMetrics.MEAN_CPU_UTIL": 27.670000000000005, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.7081048651153292, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 27.4125}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:49:40Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 55.0, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-x86_64_rtx_3060Ti.json b/results/stereo_image_proc_graph-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..862659f --- /dev/null +++ b/results/stereo_image_proc_graph-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4977.126220703125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 83.3236344984603, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 81.85895089108652, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 7.666666666666667, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 415.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 29.4296875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 25.601725260416668, "BasicPerformanceMetrics.MAX_JITTER": 12.1376953125, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 1.6228791034867611, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.6015127181854554, "CPUProfilingMetrics.MAX_CPU_UTIL": 18.394999999999996, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.15, "CPUProfilingMetrics.MEAN_CPU_UTIL": 8.052272727272726, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 8.07586079400801, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 16.793333333333333, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4907.113037109375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20255153459228, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.189290448759138, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 25.2587890625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 31.636962890625, "BasicPerformanceMetrics.MAX_JITTER": 23.13720703125, "BasicPerformanceMetrics.MIN_JITTER": 0.300048828125, "BasicPerformanceMetrics.MEAN_JITTER": 8.233266194661459, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.620445427909952, "CPUProfilingMetrics.MAX_CPU_UTIL": 6.285000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.3, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.381, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.0543784899171649, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.3549999999999995}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4990.29833984375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19935451281316, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.11664625433862, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 23.507568359375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 30.36376953125, "BasicPerformanceMetrics.MAX_JITTER": 15.264404296875, "BasicPerformanceMetrics.MIN_JITTER": 0.010009765625, "BasicPerformanceMetrics.MEAN_JITTER": 4.347942992344799, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.165227490763786, "CPUProfilingMetrics.MAX_CPU_UTIL": 14.419999999999998, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.8, "CPUProfilingMetrics.MEAN_CPU_UTIL": 11.718333333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.88940918948519, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 13.679999999999998}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4960.560791015625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200149722747486, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.23851663539215, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.814208984375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.51220703125, "BasicPerformanceMetrics.MAX_JITTER": 34.084716796875, "BasicPerformanceMetrics.MIN_JITTER": 0.05224609375, "BasicPerformanceMetrics.MEAN_JITTER": 12.044022843644425, "BasicPerformanceMetrics.STD_DEV_JITTER": 8.268137082145508, "CPUProfilingMetrics.MAX_CPU_UTIL": 9.105, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.8949999999999999, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.123333333333336, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.815548594659466, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 9.105}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:47:14Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 83.125, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_graph-x86_64_rtx_4090.json b/results/stereo_image_proc_graph-x86_64_rtx_4090.json new file mode 100644 index 0000000..061a185 --- /dev/null +++ b/results/stereo_image_proc_graph-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4982.580240885417, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 99.57590878094028, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 99.54682026279319, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 496.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.53662109375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 17.879557291666668, "BasicPerformanceMetrics.MAX_JITTER": 14.16845703125, "BasicPerformanceMetrics.MIN_JITTER": 0.001708984375, "BasicPerformanceMetrics.MEAN_JITTER": 2.5157851246204452, "BasicPerformanceMetrics.STD_DEV_JITTER": 2.1256879185991333, "CPUProfilingMetrics.MAX_CPU_UTIL": 22.6875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 18.180555555555554, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 7.714509727122446, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 21.520833333333332, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4921.05224609375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.202934270236373, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.16042860339253, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.532958984375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 37.0341796875, "BasicPerformanceMetrics.MAX_JITTER": 43.54931640625, "BasicPerformanceMetrics.MIN_JITTER": 1.344482421875, "BasicPerformanceMetrics.MEAN_JITTER": 16.28441874186198, "BasicPerformanceMetrics.STD_DEV_JITTER": 11.452853603093246, "CPUProfilingMetrics.MAX_CPU_UTIL": 5.65625, "CPUProfilingMetrics.MIN_CPU_UTIL": 5.15625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 5.4225, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.16618889854620253, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 5.46875}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4976.801513671875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.20024813005919, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.279679463981786, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 26.36669921875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 19.800048828125, "BasicPerformanceMetrics.MAX_JITTER": 18.96240234375, "BasicPerformanceMetrics.MIN_JITTER": 0.06689453125, "BasicPerformanceMetrics.MEAN_JITTER": 4.598088002044882, "BasicPerformanceMetrics.STD_DEV_JITTER": 3.458856618281167, "CPUProfilingMetrics.MAX_CPU_UTIL": 14.6875, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.675, "CPUProfilingMetrics.MEAN_CPU_UTIL": 11.831249999999999, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.57544112172076, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.4375}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4986.2861328125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200436225246296, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.082509508011913, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 18.07568359375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 37.546142578125, "BasicPerformanceMetrics.MAX_JITTER": 44.578125, "BasicPerformanceMetrics.MIN_JITTER": 0.026123046875, "BasicPerformanceMetrics.MEAN_JITTER": 15.630829682221284, "BasicPerformanceMetrics.STD_DEV_JITTER": 10.909452742484575, "CPUProfilingMetrics.MAX_CPU_UTIL": 11.3875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 9.270833333333334, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.821232599095335, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.51875}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "Stereo Image Pointcloud Graph Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_graph.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:56:24Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 99.375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: Stereo Image Pointcloud Graph Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 100\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-agx_orin.json b/results/stereo_image_proc_node-agx_orin.json new file mode 100644 index 0000000..46dd3f7 --- /dev/null +++ b/results/stereo_image_proc_node-agx_orin.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4995.03564453125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 72.07488521310766, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 68.33452470623823, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 17.666666666666668, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 359.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.812825520833334, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 28.928548177083332, "BasicPerformanceMetrics.MAX_JITTER": 2.144775390625, "BasicPerformanceMetrics.MIN_JITTER": 0.000732421875, "BasicPerformanceMetrics.MEAN_JITTER": 0.2670819217828171, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.3029034156579504, "CPUProfilingMetrics.MAX_CPU_UTIL": 28.224999999999998, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.08333333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 13.740277777777777, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 13.178815642360826, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 26.41111111111111, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.033447265625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203899115125642, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.204011980347113, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.76416015625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 14.7099609375, "BasicPerformanceMetrics.MAX_JITTER": 0.81494140625, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 0.14880879720052084, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.14483065985971452, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.733333333333333, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.75, "CPUProfilingMetrics.MEAN_CPU_UTIL": 4.036666666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.38230296304835987, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 4.733333333333333}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.187744140625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.20000629043035, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.20242772364911, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.607421875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 14.406982421875, "BasicPerformanceMetrics.MAX_JITTER": 1.001220703125, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 0.12787643535025167, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.114813616802264, "CPUProfilingMetrics.MAX_CPU_UTIL": 22.15833333333333, "CPUProfilingMetrics.MIN_CPU_UTIL": 21.233333333333334, "CPUProfilingMetrics.MEAN_CPU_UTIL": 21.665, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3246108781637206, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 21.775000000000002}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.956298828125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20077469116095, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.19958118725348, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 14.432373046875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 14.628662109375, "BasicPerformanceMetrics.MAX_JITTER": 1.853515625, "BasicPerformanceMetrics.MIN_JITTER": 0.000244140625, "BasicPerformanceMetrics.MEAN_JITTER": 0.25778280722128377, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.2717276825324573, "CPUProfilingMetrics.MAX_CPU_UTIL": 17.991666666666664, "CPUProfilingMetrics.MIN_CPU_UTIL": 10.725, "CPUProfilingMetrics.MEAN_CPU_UTIL": 13.116666666666665, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 2.6480600865958874, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 11.125}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:32:43Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 71.875, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-agx_xavier.json b/results/stereo_image_proc_node-agx_xavier.json new file mode 100644 index 0000000..0dad621 --- /dev/null +++ b/results/stereo_image_proc_node-agx_xavier.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4993.245524088542, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.824804287534626, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 57.68564227680901, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 15.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 303.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.693440755208332, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 29.306722005208332, "BasicPerformanceMetrics.MAX_JITTER": 8.329833984375, "BasicPerformanceMetrics.MIN_JITTER": 0.001220703125, "BasicPerformanceMetrics.MEAN_JITTER": 0.8657828436957465, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.9490971595517227, "CPUProfilingMetrics.MAX_CPU_UTIL": 43.599999999999994, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 22.20064393939394, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 19.792004825070816, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 42.762499999999996, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.66064453125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.20428957840589, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.202706048580623, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.275390625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 17.035888671875, "BasicPerformanceMetrics.MAX_JITTER": 4.35400390625, "BasicPerformanceMetrics.MIN_JITTER": 0.006103515625, "BasicPerformanceMetrics.MEAN_JITTER": 0.7959798177083334, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.8959044813579639, "CPUProfilingMetrics.MAX_CPU_UTIL": 8.7, "CPUProfilingMetrics.MIN_CPU_UTIL": 7.2124999999999995, "CPUProfilingMetrics.MEAN_CPU_UTIL": 8.0125, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5071365693775199, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 8.7}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 5046.680419921875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19877352837318, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 57.46351579054204, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 10, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 17.715087890625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 80.9052734375, "BasicPerformanceMetrics.MAX_JITTER": 6.1064453125, "BasicPerformanceMetrics.MIN_JITTER": 0.00390625, "BasicPerformanceMetrics.MEAN_JITTER": 0.6780064900716146, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7221698107868595, "CPUProfilingMetrics.MAX_CPU_UTIL": 44.087500000000006, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.625, "CPUProfilingMetrics.MEAN_CPU_UTIL": 22.53875, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 20.390214756409506, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 44.0625}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4965.304443359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.200961741368577, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.209627971676706, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 18.725341796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 17.300537109375, "BasicPerformanceMetrics.MAX_JITTER": 6.87890625, "BasicPerformanceMetrics.MIN_JITTER": 0.006591796875, "BasicPerformanceMetrics.MEAN_JITTER": 0.7736239046663851, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.033188332047121, "CPUProfilingMetrics.MAX_CPU_UTIL": 24.3625, "CPUProfilingMetrics.MIN_CPU_UTIL": 20.975, "CPUProfilingMetrics.MEAN_CPU_UTIL": 22.36, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.2468560462218563, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 24.3625}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:46:32Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 60.625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-orin_nano_8gb.json b/results/stereo_image_proc_node-orin_nano_8gb.json new file mode 100644 index 0000000..f036015 --- /dev/null +++ b/results/stereo_image_proc_node-orin_nano_8gb.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4959.815511067708, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 43.950525470315085, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 43.95324776886398, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 218.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.988525390625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.681315104166668, "BasicPerformanceMetrics.MAX_JITTER": 9.36572265625, "BasicPerformanceMetrics.MIN_JITTER": 0.000732421875, "BasicPerformanceMetrics.MEAN_JITTER": 0.47135190610532407, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.7836845951580651, "CPUProfilingMetrics.MAX_CPU_UTIL": 53.13333333333333, "CPUProfilingMetrics.MIN_CPU_UTIL": 48.199999999999996, "CPUProfilingMetrics.MEAN_CPU_UTIL": 50.212222222222216, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.5479046873722322, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 51.199999999999996, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4900.484130859375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203759816447914, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.203073546374638, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.878173828125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 22.207763671875, "BasicPerformanceMetrics.MAX_JITTER": 2.76708984375, "BasicPerformanceMetrics.MIN_JITTER": 0.011962890625, "BasicPerformanceMetrics.MEAN_JITTER": 0.4642893473307292, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.5317121761222402, "CPUProfilingMetrics.MAX_CPU_UTIL": 30.783333333333335, "CPUProfilingMetrics.MIN_CPU_UTIL": 11.383333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 16.669999999999998, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 7.190142944027996, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 11.383333333333333}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.6845703125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20125568209049, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.201233413653668, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.753173828125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.7568359375, "BasicPerformanceMetrics.MAX_JITTER": 15.15087890625, "BasicPerformanceMetrics.MIN_JITTER": 0.00341796875, "BasicPerformanceMetrics.MEAN_JITTER": 0.6048419024493243, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.4963052950591917, "CPUProfilingMetrics.MAX_CPU_UTIL": 38.31666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 33.88333333333333, "CPUProfilingMetrics.MEAN_CPU_UTIL": 35.486666666666665, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.594971264108961, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 38.31666666666667}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:19:51Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Feb 1 14:17:37 PST 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 43.75, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-orin_nano_emul.json b/results/stereo_image_proc_node-orin_nano_emul.json new file mode 100644 index 0000000..721c4b3 --- /dev/null +++ b/results/stereo_image_proc_node-orin_nano_emul.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4990.686197916667, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 49.575942019153615, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 48.67640495987004, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 3.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 246.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 21.143147786458332, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 49.125244140625, "BasicPerformanceMetrics.MAX_JITTER": 8.504638671875, "BasicPerformanceMetrics.MIN_JITTER": 0.00146484375, "BasicPerformanceMetrics.MEAN_JITTER": 1.3149363620222108, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.0561890838584207, "CPUProfilingMetrics.MAX_CPU_UTIL": 53.46666666666667, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.1666666666666667, "CPUProfilingMetrics.MEAN_CPU_UTIL": 28.941111111111113, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 24.5985948798093, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 51.666666666666664, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4893.81884765625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203771509256386, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.216969928085105, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 27.7412109375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 21.4111328125, "BasicPerformanceMetrics.MAX_JITTER": 4.96533203125, "BasicPerformanceMetrics.MIN_JITTER": 0.109619140625, "BasicPerformanceMetrics.MEAN_JITTER": 2.087885538736979, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.3093857380192104, "CPUProfilingMetrics.MAX_CPU_UTIL": 38.800000000000004, "CPUProfilingMetrics.MIN_CPU_UTIL": 11.0, "CPUProfilingMetrics.MEAN_CPU_UTIL": 17.606666666666666, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 10.639102927931054, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 38.800000000000004}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4964.060302734375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20069601200399, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.21719939972825, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 22.346923828125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 19.63427734375, "BasicPerformanceMetrics.MAX_JITTER": 13.501220703125, "BasicPerformanceMetrics.MIN_JITTER": 0.010498046875, "BasicPerformanceMetrics.MEAN_JITTER": 2.194477802998311, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.9692433087801584, "CPUProfilingMetrics.MAX_CPU_UTIL": 33.35, "CPUProfilingMetrics.MIN_CPU_UTIL": 29.299999999999997, "CPUProfilingMetrics.MEAN_CPU_UTIL": 30.78666666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 1.488265209340505, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 30.816666666666666}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:50:28Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Sun Mar 19 07:55:28 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 49.375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-orin_nx.json b/results/stereo_image_proc_node-orin_nx.json new file mode 100644 index 0000000..31ca040 --- /dev/null +++ b/results/stereo_image_proc_node-orin_nx.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4982.562418619792, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.82454394234396, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.81208478436975, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 303.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.586832682291668, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 17.579833984375, "BasicPerformanceMetrics.MAX_JITTER": 6.886962890625, "BasicPerformanceMetrics.MIN_JITTER": 0.0, "BasicPerformanceMetrics.MEAN_JITTER": 0.2521875324439369, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.3751348881037766, "CPUProfilingMetrics.MAX_CPU_UTIL": 40.5875, "CPUProfilingMetrics.MIN_CPU_UTIL": 38.4875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 39.51333333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.6417793037764116, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 39.670833333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4899.7998046875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.203900640314695, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.204498549546129, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.642333984375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.355224609375, "BasicPerformanceMetrics.MAX_JITTER": 1.627685546875, "BasicPerformanceMetrics.MIN_JITTER": 0.001708984375, "BasicPerformanceMetrics.MEAN_JITTER": 0.273345947265625, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.2567193893392538, "CPUProfilingMetrics.MAX_CPU_UTIL": 7.7875, "CPUProfilingMetrics.MIN_CPU_UTIL": 6.1875, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.1450000000000005, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5260465758846834, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 7.1625}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4983.73193359375, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.198856104158125, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.19585403014867, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.147216796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.395751953125, "BasicPerformanceMetrics.MAX_JITTER": 1.013671875, "BasicPerformanceMetrics.MIN_JITTER": 0.0009765625, "BasicPerformanceMetrics.MEAN_JITTER": 0.2756257537227349, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.20535864248757477, "CPUProfilingMetrics.MAX_CPU_UTIL": 39.65, "CPUProfilingMetrics.MIN_CPU_UTIL": 38.175, "CPUProfilingMetrics.MEAN_CPU_UTIL": 38.8575, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.5159093912694361, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 39.1875}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4966.68994140625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.20090532915718, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.201200753339062, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 16.31591796875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.267333984375, "BasicPerformanceMetrics.MAX_JITTER": 3.681884765625, "BasicPerformanceMetrics.MIN_JITTER": 0.005126953125, "BasicPerformanceMetrics.MEAN_JITTER": 0.30270468222128377, "BasicPerformanceMetrics.STD_DEV_JITTER": 0.40624893321712646, "CPUProfilingMetrics.MAX_CPU_UTIL": 20.375, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.375, "CPUProfilingMetrics.MEAN_CPU_UTIL": 15.970833333333331, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 7.023704902368518, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 19.424999999999997}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T06:36:21Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "aarch64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.10.104-tegra #1 SMP PREEMPT Wed Mar 15 00:17:07 PDT 2023", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 60.625, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-x86_64_rtx_3060Ti.json b/results/stereo_image_proc_node-x86_64_rtx_3060Ti.json new file mode 100644 index 0000000..169d2bd --- /dev/null +++ b/results/stereo_image_proc_node-x86_64_rtx_3060Ti.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4978.753824869792, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 99.57312858571997, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 99.45259723538824, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.6666666666666666, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 496.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 10.986979166666666, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.932861328125, "BasicPerformanceMetrics.MAX_JITTER": 10.3037109375, "BasicPerformanceMetrics.MIN_JITTER": 0.005615234375, "BasicPerformanceMetrics.MEAN_JITTER": 2.4614703505324544, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.8152811847845047, "CPUProfilingMetrics.MAX_CPU_UTIL": 15.645, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.15, "CPUProfilingMetrics.MEAN_CPU_UTIL": 8.738661616161615, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 6.186072585577951, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 14.15333333333333, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4904.865478515625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.202709098245911, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.193959491653919, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 8.463134765625, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 12.66943359375, "BasicPerformanceMetrics.MAX_JITTER": 26.15234375, "BasicPerformanceMetrics.MIN_JITTER": 0.40087890625, "BasicPerformanceMetrics.MEAN_JITTER": 5.2234649658203125, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.187963002618277, "CPUProfilingMetrics.MAX_CPU_UTIL": 3.22, "CPUProfilingMetrics.MIN_CPU_UTIL": 2.205, "CPUProfilingMetrics.MEAN_CPU_UTIL": 2.5220000000000002, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.3654941860002701, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 2.2600000000000002}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4980.6689453125, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.199891269825294, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.232872992360114, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 9.860595703125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.1318359375, "BasicPerformanceMetrics.MAX_JITTER": 18.32421875, "BasicPerformanceMetrics.MIN_JITTER": 0.010009765625, "BasicPerformanceMetrics.MEAN_JITTER": 5.769731150377517, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.0280294170621715, "CPUProfilingMetrics.MAX_CPU_UTIL": 12.895000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 1.05, "CPUProfilingMetrics.MEAN_CPU_UTIL": 10.446666666666667, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.253684350719451, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 12.645}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4973.29638671875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.198398167649277, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.161081973834673, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 9.983154296875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 16.128662109375, "BasicPerformanceMetrics.MAX_JITTER": 26.502197265625, "BasicPerformanceMetrics.MIN_JITTER": 0.04638671875, "BasicPerformanceMetrics.MEAN_JITTER": 7.718578441722973, "BasicPerformanceMetrics.STD_DEV_JITTER": 5.443963355716884, "CPUProfilingMetrics.MAX_CPU_UTIL": 10.165000000000001, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.65, "CPUProfilingMetrics.MEAN_CPU_UTIL": 7.598333333333333, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 3.1861505858254024, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 10.165000000000001}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T07:47:30Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.15.0-53-generic #59~20.04.1-Ubuntu SMP Thu Oct 20 15:10:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 99.375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/results/stereo_image_proc_node-x86_64_rtx_4090.json b/results/stereo_image_proc_node-x86_64_rtx_4090.json new file mode 100644 index 0000000..e980d11 --- /dev/null +++ b/results/stereo_image_proc_node-x86_64_rtx_4090.json @@ -0,0 +1 @@ +{"BasicPerformanceMetrics.RECEIVED_DURATION": 4981.726399739583, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 99.57505307337055, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 99.56387839072791, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0.0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 496.0, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.712158203125, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 7.0380859375, "BasicPerformanceMetrics.MAX_JITTER": 10.711669921875, "BasicPerformanceMetrics.MIN_JITTER": 0.0029296875, "BasicPerformanceMetrics.MEAN_JITTER": 2.643411860292257, "BasicPerformanceMetrics.STD_DEV_JITTER": 1.9592918739352223, "CPUProfilingMetrics.MAX_CPU_UTIL": 16.71875, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.3125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 13.312152777777778, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 5.753066847033413, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 16.483333333333334, "10.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4919.52294921875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 10.202730954233827, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 10.163587103082891, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 50, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.3671875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 25.241455078125, "BasicPerformanceMetrics.MAX_JITTER": 30.331298828125, "BasicPerformanceMetrics.MIN_JITTER": 0.074462890625, "BasicPerformanceMetrics.MEAN_JITTER": 10.9998779296875, "BasicPerformanceMetrics.STD_DEV_JITTER": 8.406603841767762, "CPUProfilingMetrics.MAX_CPU_UTIL": 4.03125, "CPUProfilingMetrics.MIN_CPU_UTIL": 3.13125, "CPUProfilingMetrics.MEAN_CPU_UTIL": 3.6925, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 0.33887221042747073, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 3.13125}, "60.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4986.103515625, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 60.19899471402073, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 60.16722257367644, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 300, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 7.059326171875, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 9.69091796875, "BasicPerformanceMetrics.MAX_JITTER": 21.207763671875, "BasicPerformanceMetrics.MIN_JITTER": 0.00048828125, "BasicPerformanceMetrics.MEAN_JITTER": 6.1489945994127515, "BasicPerformanceMetrics.STD_DEV_JITTER": 4.603978795955942, "CPUProfilingMetrics.MAX_CPU_UTIL": 15.1625, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.25, "CPUProfilingMetrics.MEAN_CPU_UTIL": 11.625, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 5.134674557603432, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 12.96875}, "30.0fps": {"BasicPerformanceMetrics.RECEIVED_DURATION": 4974.57763671875, "BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE": 30.197506140135008, "BasicPerformanceMetrics.MEAN_FRAME_RATE": 30.153313698997884, "BasicPerformanceMetrics.NUM_MISSED_FRAMES": 0, "BasicPerformanceMetrics.NUM_FRAMES_SENT": 150, "BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY": 6.163818359375, "BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY": 13.44384765625, "BasicPerformanceMetrics.MAX_JITTER": 35.90087890625, "BasicPerformanceMetrics.MIN_JITTER": 0.0234375, "BasicPerformanceMetrics.MEAN_JITTER": 10.758541622677365, "BasicPerformanceMetrics.STD_DEV_JITTER": 7.36917747237805, "CPUProfilingMetrics.MAX_CPU_UTIL": 13.75, "CPUProfilingMetrics.MIN_CPU_UTIL": 0.5, "CPUProfilingMetrics.MEAN_CPU_UTIL": 10.551041666666665, "CPUProfilingMetrics.STD_DEV_CPU_UTIL": 4.550767472857066, "CPUProfilingMetrics.BASELINE_CPU_UTIL": 11.4625}, "custom": {"data_resolution": "Quarter HD (960,540)"}, "metadata": {"BenchmarkMetadata.NAME": "stereo_image_proc::DisparityNode Benchmark", "BenchmarkMetadata.TEST_FILE_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/scripts/stereo_image_proc_node.py", "BenchmarkMetadata.TEST_DATETIME": "2023-04-04T10:47:16Z", "BenchmarkMetadata.DEVICE_HOSTNAME": "ros", "BenchmarkMetadata.DEVICE_ARCH": "x86_64", "BenchmarkMetadata.DEVICE_OS": "Linux 5.4.0-131-generic #147-Ubuntu SMP Fri Oct 14 17:07:22 UTC 2022", "BenchmarkMetadata.BENCHMARK_MODE": 1, "BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION": 99.375, "BenchmarkMetadata.INPUT_DATA_PATH": "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets/datasets/r2b_dataset/r2b_hideaway", "BenchmarkMetadata.INPUT_DATA_SIZE": 1913946112, "BenchmarkMetadata.INPUT_DATA_HASH": "96a3c2b8007173f9da57e848b4fcee8c", "BenchmarkMetadata.CONFIG": "ros2_benchmark_config:\n additional_fixed_publisher_rate_tests:\n - 10.0\n - 30.0\n - 60.0\n assets_root: /workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets\n benchmark_duration: 5.0\n benchmark_mode: BenchmarkMode.LOOPING\n benchmark_name: stereo_image_proc::DisparityNode Benchmark\n benchmark_namespace: r2b\n binary_search_acceptable_frame_loss_fraction: 0.05\n binary_search_acceptable_frame_rate_drop: 10.0\n binary_search_duration_fraction: 1.0\n binary_search_terminal_interval_width: 10.0\n cpu_profiling_interval_sec: 1.0\n custom_report_info:\n data_resolution: Resolution(960, 540, Quarter HD)\n default_config_version: 0.30.0\n default_service_future_timeout_sec: 15.0\n enable_cpu_profiler: true\n enforce_publisher_rate: false\n input_data_end_time: -1.0\n input_data_path: datasets/r2b_dataset/r2b_hideaway\n input_data_start_time: -1.0\n linear_scan_acceptable_frame_loss_fraction: 0.01\n linear_scan_acceptable_frame_rate_drop: 5.0\n linear_scan_duration_fraction: 1.0\n linear_scan_step_size: 5.0\n load_data_in_real_time: false\n log_file_name: kpi.json\n log_folder: /output\n monitor_info_list:\n - calculators:\n - class_name: BasicPerformanceCalculator\n config:\n report_prefix: ''\n module_name: ros2_benchmark.basic_performance_calculator\n service_name: start_monitoring0\n play_messages_service_future_timeout_sec: 15.0\n playback_message_buffer_size: 50\n publish_tf_messages_in_set_data: false\n publish_tf_static_messages_in_set_data: false\n publisher_lower_frequency: 10.0\n publisher_upper_frequency: 100.0\n record_data_timeline: false\n revise_timestamps_as_message_ids: false\n set_data_service_future_timeout_sec: 60.0\n setup_service_client_timeout_sec: 20.0\n start_monitoring_service_timeout_sec: 10\n start_recording_service_future_timeout_sec: 35.0\n start_recording_service_timeout_sec: 30\n test_iterations: 5\n"}} \ No newline at end of file diff --git a/ros2_benchmark/CMakeLists.txt b/ros2_benchmark/CMakeLists.txt new file mode 100644 index 0000000..401a32d --- /dev/null +++ b/ros2_benchmark/CMakeLists.txt @@ -0,0 +1,96 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.5) +project(ros2_benchmark) + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Default to Release build +if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE "Release" CACHE STRING "" FORCE) +endif() +message( STATUS "CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}" ) + +find_package(ament_cmake_auto REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(rclcpp REQUIRED) + +ament_auto_find_build_dependencies() + +ament_python_install_package(${PROJECT_NAME}) + +# OpenSSL library +find_package(OpenSSL REQUIRED) + +################################### +# Dataloader Node # +################################### +ament_auto_add_library(data_loader_node SHARED + src/data_loader_node.cpp +) +target_compile_definitions(data_loader_node + PRIVATE "COMPOSITION_BUILDING_DLL" +) +target_link_libraries(data_loader_node OpenSSL::Crypto) +rclcpp_components_register_nodes(data_loader_node "ros2_benchmark::DataLoaderNode") +set(node_plugins "${node_plugins}ros2_benchmark::DataLoaderNode;$\n") + +################################### +# Playback Node # +################################### +ament_auto_add_library(playback_node SHARED + src/playback_node.cpp +) +target_compile_definitions(playback_node + PRIVATE "COMPOSITION_BUILDING_DLL" +) +rclcpp_components_register_nodes(playback_node "ros2_benchmark::PlaybackNode") +set(node_plugins "${node_plugins}ros2_benchmark::PlaybackNode;$\n") + +################################### +# Monitor Node # +################################### +ament_auto_add_library(monitor_node SHARED + src/monitor_node.cpp +) +target_compile_definitions(monitor_node + PRIVATE "COMPOSITION_BUILDING_DLL" +) +rclcpp_components_register_nodes(monitor_node "ros2_benchmark::MonitorNode") +set(node_plugins "${node_plugins}ros2_benchmark::MonitorNode;$\n") + + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + + ament_lint_auto_find_test_dependencies() + + find_package(launch_testing_ament_cmake REQUIRED) + add_launch_test(test/data_loader_node_pol.py TIMEOUT "15") + add_launch_test(test/monitor_node_pol.py TIMEOUT "15") + add_launch_test(test/playback_node_pol.py TIMEOUT "15") +endif() + +ament_auto_package() diff --git a/ros2_benchmark/include/ros2_benchmark/common.hpp b/ros2_benchmark/include/ros2_benchmark/common.hpp new file mode 100644 index 0000000..4ba028d --- /dev/null +++ b/ros2_benchmark/include/ros2_benchmark/common.hpp @@ -0,0 +1,38 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ROS2_BENCHMARK__COMMON_HPP_ +#define ROS2_BENCHMARK__COMMON_HPP_ + +#include "rclcpp/rclcpp.hpp" + +namespace ros2_benchmark +{ + +/// Quality-of-Service policy that will drop any messages due to queue size +/// ROS 2 intraprocess communications is only compatible with keep_last policy +const rclcpp::QoS kQoS{{RMW_QOS_POLICY_HISTORY_KEEP_LAST, 1000}}; + +/// Quality-of-Service policy that will not drop any messages +const rclcpp::QoS kBufferQoS{ + {RMW_QOS_POLICY_HISTORY_KEEP_LAST, 1000}, rmw_qos_profile_parameters}; + +const int kThreadDelay{50}; + +} // namespace ros2_benchmark + +#endif // ROS2_BENCHMARK__COMMON_HPP_ diff --git a/ros2_benchmark/include/ros2_benchmark/data_loader_node.hpp b/ros2_benchmark/include/ros2_benchmark/data_loader_node.hpp new file mode 100644 index 0000000..2ea0844 --- /dev/null +++ b/ros2_benchmark/include/ros2_benchmark/data_loader_node.hpp @@ -0,0 +1,153 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ROS2_BENCHMARK__DATA_LOADER_NODE_HPP_ +#define ROS2_BENCHMARK__DATA_LOADER_NODE_HPP_ + +#include +#include +#include +#include +#include + +#include "common.hpp" + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/serialization.hpp" + +#include "rosbag2_compression_zstd/zstd_decompressor.hpp" +#include "rosbag2_cpp/typesupport_helpers.hpp" +#include "rosbag2_cpp/readers/sequential_reader.hpp" +#include "rosbag2_cpp/storage_options.hpp" +#include "rosbag2_cpp/converter_options.hpp" + +#include "std_msgs/msg/header.hpp" + +#include "ros2_benchmark_interfaces/srv/set_data.hpp" +#include "ros2_benchmark_interfaces/srv/start_loading.hpp" +#include "ros2_benchmark_interfaces/srv/stop_loading.hpp" +#include "ros2_benchmark_interfaces/srv/get_topic_message_timestamps.hpp" + +namespace ros2_benchmark +{ + +/// A data loader node for loading messages from a rosbag. +class DataLoaderNode : public rclcpp::Node +{ +public: + /// Construct a new DataLoaderNode object. + explicit DataLoaderNode(const rclcpp::NodeOptions &); + + /// Destroy this node. + ~DataLoaderNode(); + +private: + /// Callback function for handling the set_data service. + void SetDataServiceCallback( + const ros2_benchmark_interfaces::srv::SetData::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::SetData::Response::SharedPtr response); + + /// Callback function for handling the start_loading service. + void StartLoadingServiceCallback( + const ros2_benchmark_interfaces::srv::StartLoading::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::StartLoading::Response::SharedPtr response); + + /// Callback function for handling the stop_loading service. + void StopLoadingServiceCallback( + const ros2_benchmark_interfaces::srv::StopLoading::Request::SharedPtr, + ros2_benchmark_interfaces::srv::StopLoading::Response::SharedPtr); + + /// Callback function for handling the get_topic_message_timestamps service. + void GetTopicMessageTimestampsSereviceCallback( + const ros2_benchmark_interfaces::srv::GetTopicMessageTimestamps::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::GetTopicMessageTimestamps::Response::SharedPtr response); + + /// Create a TopicMessageTimestampArray message from the loaded message timeline. + std::vector + CreateTopicMessageTimestampArrayMessageList( + const int64_t start_time_ns, + const int64_t end_time_ns); + + /// Use rosbag_reader_ to open the rosbag file located in the path rosbag_path_. + void OpenRosbagFile(); + + /// Publish the given serialized rosbag message with the specified publisher + void PublishMessage( + std::shared_ptr publisher, + std::shared_ptr message); + + /// Callback group for services. + const rclcpp::CallbackGroup::SharedPtr service_callback_group_; + + /// A service object for SetData. + const rclcpp::Service::SharedPtr + set_data_service_; + + /// A service object for StartLoading. + const rclcpp::Service::SharedPtr + start_loading_service_; + + /// A service object for StopLoading. + const rclcpp::Service::SharedPtr + stop_loading_service_; + + /// A service object for GetTopicMessageTimestamps. + const rclcpp::Service::SharedPtr + get_topic_message_timestamps_service_; + + /// The path of the rosbag to be loaded. + std::string rosbag_path_ {""}; + + /// The earlies timestamp observed in the loaded rosbag. + int64_t first_timestamp_ns_ {0}; + + /// The latest timestamp observed in the loaded rosbag. + int64_t last_timestamp_ns_ {0}; + + /// Timeline (rosbag-recorded timestamps) of the messages loaded from the rosbag. + std::unordered_map> topic_message_timestamps_; + + /// The publisher rate for publishing messages loaded from rosbag. + /// It is ignored when requested to publish messages in real-time via the + /// StartLoading service request (the publish_in_real_time field). + int64_t publisher_period_ms_; + + /// Counter for tracking the number of messages being published. + uint64_t played_message_count_ {0}; + + bool stop_playing_ {false}; + std::mutex stop_playing_mutex_; + + /// A rosbag reader. + rosbag2_cpp::readers::SequentialReader rosbag_reader_; + + /// A zstd message decompressor. + rosbag2_compression_zstd::ZstdDecompressor decompressor_; + + /// Whether messages in the loaded rosbag are zstd-message-compressed. + bool is_rosbag_compressed_ {false}; + + /// Generic publishers for all topics available from the loaded rosbag. + std::unordered_map> publishers_; + + /// Dedicated publishers for TF messages + std::unordered_map> tf_publishers_; +}; + +} // namespace ros2_benchmark + +#endif // ROS2_BENCHMARK__DATA_LOADER_NODE_HPP_ diff --git a/ros2_benchmark/include/ros2_benchmark/monitor_node.hpp b/ros2_benchmark/include/ros2_benchmark/monitor_node.hpp new file mode 100644 index 0000000..76661fd --- /dev/null +++ b/ros2_benchmark/include/ros2_benchmark/monitor_node.hpp @@ -0,0 +1,99 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ROS2_BENCHMARK__MONITOR_NODE_HPP_ +#define ROS2_BENCHMARK__MONITOR_NODE_HPP_ + +#include +#include +#include + +#include "common.hpp" + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/serialization.hpp" + +#include "ros2_benchmark_interfaces/srv/start_monitoring.hpp" + + +namespace ros2_benchmark +{ + +using TimePt = std::chrono::time_point; +using KeyTimePtMap = std::map; + +constexpr char kMonitorNodeServiceBaseName[] = "start_monitoring"; + +class MonitorNode : public rclcpp::Node +{ +public: + /// Construct a new MonitorNode object. + explicit MonitorNode(const rclcpp::NodeOptions &); + + /// Construct a new MonitorNode object with a custom node name. + explicit MonitorNode(const std::string &, const rclcpp::NodeOptions &); + +protected: + /// Create a generic type monitor subscriber. + void CreateGenericTypeMonitorSubscriber(); + + /// A subscriber callback function for generic ROS type message monitor + /// (that adds end timestamps). + void GenericMonitorSubscriberCallback( + std::shared_ptr serialized_message_ptr); + + /// Callback function to start monitoring the incoming messages. + void StartMonitoringServiceCallback( + const ros2_benchmark_interfaces::srv::StartMonitoring::Request::SharedPtr, + ros2_benchmark_interfaces::srv::StartMonitoring::Response::SharedPtr response); + + /// Record an end timestamp for a given message key. + bool RecordEndTimestamp(const int32_t & message_key); + + /// Record an end timestamp with an automatic generated key. + bool RecordEndTimestampAutoKey(); + + /// Index of this monitor node. + uint32_t monitor_index_; + + /// The name of the service StartMonitoring created in this nodee + std::string monitor_service_name_; + + /// Data format of the monitor subscriber. + std::string monitor_data_format_; + + /// Treat the header.stamp.sec field in a message as a message ID. + bool revise_timestamps_as_message_ids_{false}; + + /// A subscriber that monitors the incoming messages for a specified topic + /// and record their arrival timestamps. + std::shared_ptr monitor_sub_{nullptr}; + + /// A list for storing timestamps of the observed messages. + KeyTimePtMap end_timestamps_{}; + + /// Callback group for services. + const rclcpp::CallbackGroup::SharedPtr service_callback_group_; + + /// A service object for StartMonitoring. + rclcpp::Service::SharedPtr + start_monitoring_service_; +}; + +} // namespace ros2_benchmark + +#endif // ROS2_BENCHMARK__MONITOR_NODE_HPP_ diff --git a/ros2_benchmark/include/ros2_benchmark/playback_node.hpp b/ros2_benchmark/include/ros2_benchmark/playback_node.hpp new file mode 100644 index 0000000..c1b91a2 --- /dev/null +++ b/ros2_benchmark/include/ros2_benchmark/playback_node.hpp @@ -0,0 +1,197 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ROS2_BENCHMARK__PLAYBACK_NODE_HPP_ +#define ROS2_BENCHMARK__PLAYBACK_NODE_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include "common.hpp" + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/serialization.hpp" + +#include "ros2_benchmark_interfaces/srv/play_messages.hpp" +#include "ros2_benchmark_interfaces/srv/start_recording.hpp" +#include "ros2_benchmark_interfaces/srv/stop_recording.hpp" + +#include "std_msgs/msg/header.hpp" + +namespace ros2_benchmark +{ + +using TimePt = std::chrono::time_point; +using KeyTimePtMap = std::map; + +class PlaybackNode : public rclcpp::Node +{ +public: + /// Construct a new PlaybackNode object. + explicit PlaybackNode(const rclcpp::NodeOptions &); + + /// Construct a new PlaybackNode object with a custom node name. + explicit PlaybackNode(const std::string &, const rclcpp::NodeOptions &); + +protected: + /// Create a pair of publisher and subscriber for the given data format. + void CreateGenericPubSub(const std::string data_format, const size_t index); + + /// Check if all the expected number of messages are buffered. + virtual bool AreBuffersFull() const; + + /// Clear all the message buffers. + virtual void ClearBuffers(); + + /// Publish a message with the given index from each of the publishers. + void PublishGroupMessages( + size_t index, + const std_msgs::msg::Header & header); + + /// Publish a buffered message from the selected publisher with revised a timestamp. + virtual bool PublishMessage( + const size_t pub_index, + const size_t message_index, + const std::optional & header); + + /// Callback function for handling the start_recording service. + void StartRecordingServiceCallback( + const ros2_benchmark_interfaces::srv::StartRecording::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::StartRecording::Response::SharedPtr response); + + /// Callback function for handling the stop_recording service. + void StopRecordingServiceCallback( + const ros2_benchmark_interfaces::srv::StopRecording::Request::SharedPtr, + ros2_benchmark_interfaces::srv::StopRecording::Response::SharedPtr); + + /// Callback function for handling the play_messages service. + void PlayMessagesServiceCallback( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response); + + /// A subscriber callback function for recording the received messages. + void GenericTypeRecordingSubscriberCallback( + std::shared_ptr serialized_message_ptr, + size_t buffer_index); + + /// Publish the buffered messages in a timeline playback mode. + void PlayMessagesTimelinePlayback( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response); + + /// Publish the buffered messages in a looping/sweeeping playback mode. + void PlayMessagesLoopingSweeping( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response); + + /// Record a timestamp for a specified message key. + bool RecordStartTimestamp(const int64_t & message_key); + + /// Add a message timestamp for a topic in timestamps_to_messages_map_. + void AddToTimestampsToMessagesMap( + uint64_t timestamp, + size_t pub_index, + size_t message_index); + + /// Get the count of all the recorded messages. + virtual uint64_t GetRecordedMessageCount() const; + + /// Get the count of the recorded messages for the specified pub/sub index. + virtual uint64_t GetRecordedMessageCount(size_t pub_index) const; + + /// Get the number of publishers created in this node. + virtual size_t GetPublisherCount() const; + + /// Get all the topic names recorded from this node. + const std::vector GetRecordedTopicNames(); + + /// Get the total number of timestamps stored in the message timeline variable. + uint64_t GetTimestampsToMessagesCount() const; + + /// Callback group for services. + const rclcpp::CallbackGroup::SharedPtr service_callback_group_; + + /// A service object for StartRecording. + const rclcpp::Service::SharedPtr + start_recording_service_; + + /// A service object for StopRecording. + const rclcpp::Service::SharedPtr + stop_recording_service_; + + /// A service object for PlayMessages. + const rclcpp::Service::SharedPtr + play_messages_service_; + + /// Counter for tracking the number of messages published to produce unique keys. + int message_counter_{0}; + + std::mutex stop_recording_mutex_; + std::mutex buffers_mutex_; + bool stop_recording_; + + /// The number of messages that need to be buffered on each topic set from a + /// StartRecording service request. All incoming messages are buffered if set to 0. + size_t requested_buffer_length_; + + /// The maximum number of messages can be buffered in this node for each topic. + /// It has higher condition priority than th length set in requested_buffer_length_. + const size_t max_size_; + + /// A list for storing timestamps when messags are publishd. + KeyTimePtMap start_timestamps_{}; + + /// Treat the header.stamp.sec field in a message as a message ID. + bool revise_timestamps_as_message_ids_{false}; + + /// Data formats of the messages received and published by this node. + std::vector data_formats_; + + /// A topic name translation for matching the topic names of a data loadr node. + /// It must be provided via the node's parameter in order to enable the timeline + /// playback mode to store message timeline information provided from a data + /// loader node correctly when there is one or more nodes present in between the + /// data loader node and the current node. The index in this list matches the index + /// of the pubs/subs created in this node. + std::vector timeline_topic_name_translations_; + + /// Buffers for storing serialized message pointers (of any ROS message types). + std::unordered_map>> + serialized_msg_buffers_{}; + + /// Subscribers for buffering incoming messages. + std::unordered_map> subs_; + + /// Generic publishers that publish the buffered serialized messages. + std::unordered_map> generic_pubs_; + + /// Publisher/message indeices with ordered timestamps as keys. + /// The value is a list of publisher/message index pairs. + std::map>> timestamps_to_messages_map_; + + /// Whether to enable timeline recording in the start_recording service + bool record_data_timeline_{false}; +}; + +} // namespace ros2_benchmark + +#endif // ROS2_BENCHMARK__PLAYBACK_NODE_HPP_ diff --git a/ros2_benchmark/package.xml b/ros2_benchmark/package.xml new file mode 100644 index 0000000..1664c0d --- /dev/null +++ b/ros2_benchmark/package.xml @@ -0,0 +1,51 @@ + + + + + + + ros2_benchmark + 0.30.0 + Benchmarking framework for ROS 2 graphs + + Hemal Shah + Apache-2.0 + https://developer.nvidia.com/isaac-ros-gems/ + CY Chen + Jaiveer Singh + Yuankun Zhu + + ament_cmake_auto + + rclcpp + rclcpp_action + rclcpp_components + ros2_benchmark_interfaces + rosbag2_compression_zstd + rosbag2_cpp + rosbag2_py + std_msgs + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros2_benchmark/ros2_benchmark/__init__.py b/ros2_benchmark/ros2_benchmark/__init__.py new file mode 100644 index 0000000..b693a6c --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/__init__.py @@ -0,0 +1,36 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +"""Imports for ros2_benchmark module.""" + +from .basic_performance_calculator import BasicPerformanceCalculator, BasicPerformanceMetrics +from .ros2_benchmark_config import BenchmarkMode, MonitorPerformanceCalculatorsInfo +from .ros2_benchmark_config import ROS2BenchmarkConfig +from .ros2_benchmark_test import BenchmarkMetadata, ROS2BenchmarkTest +from .utils.image_utility import ImageResolution, Resolution + +__all__ = [ + 'BasicPerformanceCalculator', + 'BasicPerformanceMetrics', + 'BenchmarkMetadata', + 'BenchmarkMode', + 'ImageResolution', + 'MonitorPerformanceCalculatorsInfo', + 'Resolution', + 'ROS2BenchmarkConfig', + 'ROS2BenchmarkTest', +] diff --git a/ros2_benchmark/ros2_benchmark/basic_performance_calculator.py b/ros2_benchmark/ros2_benchmark/basic_performance_calculator.py new file mode 100644 index 0000000..aafe493 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/basic_performance_calculator.py @@ -0,0 +1,218 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum +import numbers + +import numpy +import rclpy + + +class BasicPerformanceMetrics(Enum): + """Basic performance metrics.""" + + RECEIVED_DURATION = 'Delta between First & Last Received Frames (ms)' + MEAN_PLAYBACK_FRAME_RATE = 'Mean Playback Frame Rate (fps)' + MEAN_FRAME_RATE = 'Mean Frame Rate (fps)' + NUM_MISSED_FRAMES = '# of Missed Frames' + NUM_FRAMES_SENT = '# of Frames Sent' + FIRST_SENT_RECEIVED_LATENCY = 'First Sent to First Received Latency (ms)' + LAST_SENT_RECEIVED_LATENCY = 'Last Sent to Last Received Latency (ms)' + FIRST_INPUT_LATENCY = 'First Frame End-to-end Latency (ms)' + LAST_INPUT_LATENCY = 'Last Frame End-to-end Latency (ms)' + MAX_LATENCY = 'Max. End-to-End Latency (ms)' + MIN_LATENCY = 'Min. End-to-End Latency (ms)' + MEAN_LATENCY = 'Mean End-to-End Latency (ms)' + MAX_JITTER = 'Max. Frame-to-Frame Jitter (ms)' + MIN_JITTER = 'Min. Frame-to-Frame Jitter (ms)' + MEAN_JITTER = 'Mean Frame-to-Frame Jitter (ms)' + STD_DEV_JITTER = 'Frame-to-Frame Jitter Std. Deviation (ms)' + + +class BasicPerformanceCalculator(): + """Calculator that computes performance with basic metrics.""" + + def __init__(self, config: dict = {}) -> None: + """Initialize the calculator.""" + self.config = config + self._report_prefix = config.get('report_prefix', '') + self._message_key_match = config.get('message_key_match', False) + self._logger = None + self._perf_data_list = [] + + def set_logger(self, logger): + """Set logger that enables to print log messages.""" + self._logger = logger + + def get_logger(self): + """Get logger for printing log messages.""" + if self._logger is not None: + return self._logger + return rclpy.logging.get_logger(self.__class__.__name__) + + def get_info(self): + """Return a dict containing information for loading this calculator class.""" + info = {} + info['module_name'] = self.__class__.__module__ + info['class_name'] = self.__class__.__name__ + info['config'] = self.config + return info + + def reset(self): + """Reset the calculator state.""" + self._perf_data_list.clear() + + def calculate_performance(self, + start_timestamps_ns: dict, + end_timestamps_ns: dict) -> dict: + """Calculate performance based on message start and end timestamps.""" + perf_data = {} + num_of_frame_sent = len(start_timestamps_ns) + num_of_frame_dropped = len(start_timestamps_ns) - len(end_timestamps_ns) + + # BasicPerformanceMetrics.RECEIVED_DURATION + last_end_timestamp_ms = list(end_timestamps_ns.values())[-1] / 10**6 + first_end_timestamp_ms = list(end_timestamps_ns.values())[0] / 10**6 + received_duration_ms = last_end_timestamp_ms - first_end_timestamp_ms + perf_data[BasicPerformanceMetrics.RECEIVED_DURATION] = received_duration_ms + + # BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE + if (len(start_timestamps_ns) > 1): + last_sent_time_ms = list(start_timestamps_ns.values())[-1] / 10**6 + first_sent_time_ms = list(start_timestamps_ns.values())[0] / 10**6 + sent_duration_ms = last_sent_time_ms - first_sent_time_ms + perf_data[BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE] = len( + start_timestamps_ns) / (sent_duration_ms / 1000.0) + else: + self.get_logger().warning( + 'Could not compute MEAN_PLAYBACK_FRAME_RATE due to insufficient start ' + f'timestamps received: {len(start_timestamps_ns)} was received') + + # BasicPerformanceMetrics.MEAN_FRAME_RATE + if received_duration_ms > 0: + perf_data[BasicPerformanceMetrics.MEAN_FRAME_RATE] = len( + end_timestamps_ns) / (received_duration_ms / 1000.0) + else: + self.get_logger().warning( + 'Could not compute MEAN_FRAME_RATE due to an invalid value of' + f'RECEIVED_DURATION = {received_duration_ms}') + self.get_logger().warning( + 'This could be caused by insufficient timestamps received: ' + f'#start_timestamps={len(start_timestamps_ns)} ' + f'#end_timestamps = {len(end_timestamps_ns)}') + + perf_data[BasicPerformanceMetrics.NUM_MISSED_FRAMES] = num_of_frame_dropped + perf_data[BasicPerformanceMetrics.NUM_FRAMES_SENT] = num_of_frame_sent + + perf_data[BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY] = \ + first_end_timestamp_ms - first_sent_time_ms + perf_data[BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY] = \ + last_end_timestamp_ms - last_sent_time_ms + + if self._message_key_match: + # Calculate latency between sent and received messages + end_to_end_latencies_ms = [] + for message_key, start_timestamp_ns in start_timestamps_ns.items(): + if message_key in end_timestamps_ns: + end_to_end_latencies_ms.append( + (end_timestamps_ns[message_key] - start_timestamp_ns) / 10**6) + + if len(end_to_end_latencies_ms) > 0: + perf_data[BasicPerformanceMetrics.FIRST_INPUT_LATENCY] = \ + end_to_end_latencies_ms[0] + perf_data[BasicPerformanceMetrics.LAST_INPUT_LATENCY] = \ + end_to_end_latencies_ms[-1] + perf_data[BasicPerformanceMetrics.MAX_LATENCY] = \ + max(end_to_end_latencies_ms) + perf_data[BasicPerformanceMetrics.MIN_LATENCY] = \ + min(end_to_end_latencies_ms) + perf_data[BasicPerformanceMetrics.MEAN_LATENCY] = \ + sum(end_to_end_latencies_ms) / len(end_to_end_latencies_ms) + else: + self.get_logger().warning('No end-to-end latency data available.') + + # Calculate frame-to-frame jitter if at least 3 valid end timestamps are received + if len(end_timestamps_ns) > 2: + np_end_timestamps_ms = (numpy.array(list(end_timestamps_ns.values())))/(10**6) + jitters = numpy.abs(numpy.diff(numpy.diff(np_end_timestamps_ms))) + perf_data[BasicPerformanceMetrics.MAX_JITTER] = float(numpy.max(jitters)) + perf_data[BasicPerformanceMetrics.MIN_JITTER] = float(numpy.min(jitters)) + perf_data[BasicPerformanceMetrics.MEAN_JITTER] = float(numpy.mean(jitters)) + perf_data[BasicPerformanceMetrics.STD_DEV_JITTER] = float(numpy.std( + jitters)) + else: + self.get_logger().warning( + 'Received insufficient end timestamps for calculating frame-to-frame jitters.' + f'3 were needed but only {len(end_timestamps_ns)} timestamp(s) were received.') + + # Store the current perf results to be concluded later + self._perf_data_list.append(perf_data) + + if self._report_prefix != '': + return {self._report_prefix: perf_data} + return perf_data + + def conclude_performance(self) -> dict: + """Calculate final statistical performance outcome based on all results.""" + if len(self._perf_data_list) == 0: + self.get_logger().warn('No prior performance measurements to conclude') + return {} + + MEAN_METRICS = [ + BasicPerformanceMetrics.NUM_FRAMES_SENT, + BasicPerformanceMetrics.FIRST_INPUT_LATENCY, + BasicPerformanceMetrics.LAST_INPUT_LATENCY, + BasicPerformanceMetrics.FIRST_SENT_RECEIVED_LATENCY, + BasicPerformanceMetrics.LAST_SENT_RECEIVED_LATENCY, + BasicPerformanceMetrics.MEAN_LATENCY, + BasicPerformanceMetrics.NUM_MISSED_FRAMES, + BasicPerformanceMetrics.RECEIVED_DURATION, + BasicPerformanceMetrics.MEAN_FRAME_RATE, + BasicPerformanceMetrics.STD_DEV_JITTER, + BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE, + ] + MAX_METRICS = [ + BasicPerformanceMetrics.MAX_LATENCY, + BasicPerformanceMetrics.MAX_JITTER, + BasicPerformanceMetrics.MEAN_JITTER, + ] + MIN_METRICS = [ + BasicPerformanceMetrics.MIN_LATENCY, + BasicPerformanceMetrics.MIN_JITTER, + ] + + final_perf_data = {} + for metric in BasicPerformanceMetrics: + metric_value_list = [perf_data.get(metric, None) for perf_data in self._perf_data_list] + if not all([isinstance(value, numbers.Number) for value in metric_value_list]): + continue + + # Remove the best and the worst before concluding the metric + metric_value_list.remove(max(metric_value_list)) + metric_value_list.remove(min(metric_value_list)) + + if metric in MEAN_METRICS: + final_perf_data[metric] = sum(metric_value_list)/len(metric_value_list) + elif metric in MAX_METRICS: + final_perf_data[metric] = max(metric_value_list) + elif metric in MIN_METRICS: + final_perf_data[metric] = min(metric_value_list) + else: + final_perf_data[metric] = 'INVALID VALUES: NO CONCLUDED METHOD ASSIGNED' + + self.reset() + return final_perf_data diff --git a/ros2_benchmark/ros2_benchmark/default_ros2_benchmark_config.yaml b/ros2_benchmark/ros2_benchmark/default_ros2_benchmark_config.yaml new file mode 100644 index 0000000..0642f4f --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/default_ros2_benchmark_config.yaml @@ -0,0 +1,141 @@ +%YAML 1.2 +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +--- +ros2_benchmark_config: + # Version number of this default config file + default_config_version: "0.30.0" + + # Namespace of the benchmark test + benchmark_namespace: "r2b" + + # Benchmark name to be used in performance output messages + benchmark_name: "" + + # Custom information to be included in the final report file + custom_report_info: {} + + # Benchmark mode for how buffered messages should be played. + # Can be either of "TIMELINE", "LOOPING" or "SWEEPING". + benchmark_mode: "LOOPING" + + # Use timestamp's sec field in a message header as message IDs for benchmarking + revise_timestamps_as_message_ids: false + + # Enable CPU profiling during benchmarking + enable_cpu_profiler: true + + # Enable publishing TF messages when setting data in a data loader node + publish_tf_messages_in_set_data: false + publish_tf_static_messages_in_set_data: false + + # Request a data loader node to publish messages in real-time + load_data_in_real_time: false + + # Request a playback node to record/buffer messages along with their arrival + # timestamps and use them as the message timeline + record_data_timeline: false + + # Add an additional trial buffer preparation call before the formal buffer + # preparation process + enable_trial_buffer_preparation: false + + # The interval for probing CPU utilization + cpu_profiling_interval_sec: 1 + + # Monitor node configurations + monitor_info_list: + - service_name: "start_monitoring0" + calculators: + - module_name: "ros2_benchmark.basic_performance_calculator" + class_name: "BasicPerformanceCalculator" + config: + report_prefix: "" + + # Duration, in seconds, for how long each benchmark should run + benchmark_duration: 5 + + # Amount of time to wait for a service client to be created + setup_service_client_timeout_sec: 20 + + # Amount of time for a service to complete before timing out + start_recording_service_timeout_sec: 30 + start_monitoring_service_timeout_sec: 10 + + # Amount of time to wait for a service future to return + default_service_future_timeout_sec: 15 + set_data_service_future_timeout_sec: 60 + start_recording_service_future_timeout_sec: 35 + play_messages_service_future_timeout_sec: 15 + + # The number of test iterations + test_iterations: 5 + + # The number of frames to be buffered + playback_message_buffer_size: 100 + + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency: 100.0 + publisher_lower_frequency: 10.0 + + # Whether to stop testing when the desired playback publisher rate cannot be met + enforce_publisher_rate: false + + # A list of fixed test publisher rate to be tested after the main fps benchmark test + additional_fixed_publisher_rate_tests: [10.0, 30.0, 60.0] + + # Stop binary search once upper and lower target frequencies are within this range + binary_search_terminal_interval_width: 10 # (hz) + + # Multiplier for the test duration during throughput binary search probe + binary_search_duration_fraction: 1.0 + + # Fraction of frames that can be lost without failing the test + binary_search_acceptable_frame_loss_fraction: 0.05 + + # Frame rate drop between input and output that can be tolerated without failing the test + binary_search_acceptable_frame_rate_drop: 10 # (hz) + + # Frequency, in hz, to increase the target frequency by with each step + linear_scan_step_size: 5 + + # Multiplier for the test duration during throughput linear search probe + linear_scan_duration_fraction: 1.0 + + # Fraction of frames that can be lost without failing the test + linear_scan_acceptable_frame_loss_fraction: 0.01 + + # Frame rate drop between input and output that can be tolerated without failing the test + linear_scan_acceptable_frame_rate_drop: 5 # (hz) + + # The path of the directory for exporting benchmark final report + log_folder: "/tmp" + + # The name of the file for exporting benchmark final report in the "log_folder". + # The file name is automatically generated if not set. + log_file_name: "" + + # The directory for storing assets + assets_root: "/workspaces/isaac_ros-dev/ros_ws/src/ros2_benchmark/assets" + + # The path, relative to "assets_root", of the file (usually a rosbag) to be + # loaded by a data loader node + input_data_path: "" + + # The time range (in seconds) in the data to be loaded from a data loader node + input_data_start_time: -1 + input_data_end_time: -1 diff --git a/ros2_benchmark/ros2_benchmark/ros2_benchmark_config.py b/ros2_benchmark/ros2_benchmark/ros2_benchmark_config.py new file mode 100644 index 0000000..d405db8 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/ros2_benchmark_config.py @@ -0,0 +1,192 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum +import importlib +import os +import sys + +import yaml + +from .basic_performance_calculator import BasicPerformanceCalculator +from .utils.image_utility import Resolution + +BUILTIN_ROS2_BENCHMARK_CONFIG_FILE = os.path.join( + os.path.dirname(__file__), + 'default_ros2_benchmark_config.yaml') + + +class MonitorPerformanceCalculatorsInfo: + def __init__(self, + service_name='start_monitoring0', + calculators=[BasicPerformanceCalculator()]) -> None: + """Initialize a monitor's performance calculators info.""" + self.service_name = service_name + self.calculators = calculators + + def get_info(self): + """Return a dict containing information for setting this monitor info object.""" + info = {} + info['service_name'] = self.service_name + info['calculators'] = [] + for calculator in self.calculators: + info['calculators'].append(calculator.get_info()) + return info + + +class BenchmarkMode(Enum): + """ + Benchmark modes supported in the framework. + + The enum values must match what is defined in ros2_benchmark_interfaces::srv::PlayMessage + """ + + TIMELINE = 0 + LOOPING = 1 + SWEEPING = 2 + + +class ROS2BenchmarkConfig(): + """A class that holds configurations for ros2_benchmark.""" + + __builtin_config_file_path = BUILTIN_ROS2_BENCHMARK_CONFIG_FILE + + # It is only necessary to add a parameter to this map if we want + # to enable overriding such a parameter from an env variable and + # its type is not string (as env only supports string values). + __config_type_map = { + 'revise_timestamps_as_message_ids': bool, + 'enable_cpu_profiler': bool, + 'publish_tf_messages_in_set_data': bool, + 'publish_tf_static_messages_in_set_data': bool, + 'load_data_in_real_time': bool, + 'record_data_timeline': bool, + 'cpu_profiling_interval_sec': float, + 'benchmark_duration': float, + 'setup_service_client_timeout_sec': float, + 'start_recording_service_timeout_sec': int, + 'start_monitoring_service_timeout_sec': int, + 'default_service_future_timeout_sec': float, + 'set_data_service_future_timeout_sec': float, + 'start_recording_service_future_timeout_sec': float, + 'play_messages_service_future_timeout_sec': float, + 'test_iterations': int, + 'playback_message_buffer_size': int, + 'publisher_upper_frequency': float, + 'publisher_lower_frequency': float, + 'enforce_publisher_rate': bool, + 'binary_search_terminal_interval_width': float, + 'binary_search_duration_fraction': float, + 'binary_search_acceptable_frame_loss_fraction': float, + 'binary_search_acceptable_frame_rate_drop': float, + 'linear_scan_step_size': float, + 'linear_scan_duration_fraction': float, + 'linear_scan_acceptable_frame_loss_fraction': float, + 'linear_scan_acceptable_frame_rate_drop': float, + 'input_data_start_time': float, + 'input_data_end_time': float + } + + def __init__(self, config_file_path: str = '', *args, **kw): + """Initialize default and given configs and apply to attribtues.""" + self.apply_to_attributes(dict(*args, **kw)) + + if config_file_path != '': + try: + self.apply_to_attributes( + load_config_file(config_file_path)['ros2_benchmark_config'], + override=False) + except (FileNotFoundError, yaml.YAMLError, TypeError) as error: + print('Failed to load a custom benchmark config file.') + raise error + try: + self.apply_to_attributes( + load_config_file(self.__builtin_config_file_path)['ros2_benchmark_config'], + override=False) + except (FileNotFoundError, yaml.YAMLError, TypeError) as error: + print('Failed to load a default benchmark config file.') + raise error + + def apply_to_attributes(self, config_dict, override=True): + """Apply the given configuration key-value pairs to instance attributes.""" + for key, value in config_dict.items(): + if override is False and hasattr(self, key): + continue + if key == 'benchmark_mode' and isinstance(value, str): + if value not in BenchmarkMode.__members__: + raise TypeError(f'Unknown benchmark mode: "{value}"') + setattr(self, key, BenchmarkMode.__members__[value]) + elif key == 'monitor_info_list': + monitor_info_list = [] + for monitor_info in value: + if isinstance(monitor_info, MonitorPerformanceCalculatorsInfo): + monitor_info_list.append(monitor_info) + continue + calculator_list = [] + for calculator in monitor_info['calculators']: + calculator_module = importlib.import_module(calculator['module_name']) + calculator_class = getattr(calculator_module, calculator['class_name']) + calculator_config = calculator['config'] if 'config' in calculator else {} + calculator_list.append(calculator_class(calculator_config)) + monitor_info_list.append( + MonitorPerformanceCalculatorsInfo( + monitor_info['service_name'], + calculator_list)) + setattr(self, key, monitor_info_list) + else: + if key in self.__config_type_map: + value_type = self.__config_type_map[key] + if value_type is bool and isinstance(value, str): + if value.lower() in ['false', '0']: + value = False + else: + value = True + setattr(self, key, self.__config_type_map[key](value)) + else: + setattr(self, key, value) + + def to_yaml_str(self): + """Export all configurations as a YAML string.""" + yaml.add_representer(Resolution, Resolution.yaml_representer) + + config_dict = {} + for key, value in self.__dict__.items(): + if key == 'benchmark_mode': + config_dict[key] = str(value) + elif key == 'monitor_info_list': + monitor_info_list_export = [] + for monitor_info in value: + monitor_info_list_export.append(monitor_info.get_info()) + config_dict[key] = monitor_info_list_export + else: + config_dict[key] = value + return yaml.dump({'ros2_benchmark_config': config_dict}, allow_unicode=True) + + +def load_config_file(config_file_path: str): + """Load a benchmark configuration file and return its dict object.""" + try: + with open(config_file_path) as config_file: + return yaml.safe_load(config_file.read()) + except FileNotFoundError as error: + print('Could not find benchmark config file at ' + f'"{config_file_path}".', sys.stderr) + raise error + except yaml.YAMLError as error: + print('Invalid benchmark configs detected in ' + f'"{config_file_path}".', sys.stderr) + raise error diff --git a/ros2_benchmark/ros2_benchmark/ros2_benchmark_test.py b/ros2_benchmark/ros2_benchmark/ros2_benchmark_test.py new file mode 100644 index 0000000..15cd128 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/ros2_benchmark_test.py @@ -0,0 +1,939 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import datetime +from enum import Enum +from functools import partial +import hashlib +import json +from math import ceil +import os +import platform +import sys +from typing import Iterable +import unittest + +import launch +from launch.actions import OpaqueFunction +import launch_testing.actions +import rclpy + +from ros2_benchmark_interfaces.srv import GetTopicMessageTimestamps, PlayMessages +from ros2_benchmark_interfaces.srv import SetData, StartLoading, StopLoading +from ros2_benchmark_interfaces.srv import StartMonitoring, StartRecording + +import rosbag2_py + +from .basic_performance_calculator import BasicPerformanceMetrics +from .ros2_benchmark_config import BenchmarkMode +from .ros2_benchmark_config import ROS2BenchmarkConfig +from .utils.cpu_profiler import CPUProfiler +from .utils.nsys_utility import NsysUtility +from .utils.ros2_utility import ClientUtility + + +# The maximum allowed line width of a performance repeort displayed in the terminal +MAX_REPORT_OUTPUT_WIDTH = 90 + + +class BenchmarkMetadata(Enum): + """Benchmark metadata items to be included in a final report.""" + + NAME = 'Test Name' + TEST_DATETIME = 'Test Datetime' + TEST_FILE_PATH = 'Test File Path' + DEVICE_ARCH = 'Device Architecture' + DEVICE_OS = 'Device OS' + DEVICE_HOSTNAME = 'Device Hostname' + BENCHMARK_MODE = 'Benchmark Mode' + INPUT_DATA_PATH = 'Input Data Path' + INPUT_DATA_HASH = 'Input Data Hash' + INPUT_DATA_SIZE = 'Input Data Size (bytes)' + INPUT_DATA_START_TIME = 'Input Data Start Time (s)' + INPUT_DATA_END_TIME = 'Input Data End Time (s)' + DATA_RESOLUTION = 'Data Resolution' + PEAK_THROUGHPUT_PREDICTION = 'Peak Throughput Prediction (Hz)' + CONFIG = 'Test Configurations' + + +class ROS2BenchmarkTest(unittest.TestCase): + """The main ros2_benchmark framework test class.""" + + # A config object that holds benchmark-relevant settings + config = ROS2BenchmarkConfig() + + def __init__(self, *args, **kwargs): + """Initialize ros2_benchmark.""" + # Calculated hash of the data to be loaded from a data loader node + self._input_data_hash = '' + + # Size of the data (file) + self._input_data_size_bytes = 0 + + self._test_datetime = datetime.datetime.now(datetime.timezone.utc) + + # The absolute path of the top level launch script + self._test_file_path = os.path.abspath(sys.argv[1]) + + self._peak_throughput_prediction = 0.0 + self._logger_name_stack = [''] + + # Override default configs from env variablees + self.override_config_from_env() + + self._cpu_profiler = CPUProfiler() + self._cpu_profiler_log_file_path = '' + + super().__init__(*args, **kwargs) + + @classmethod + def setUpClass(cls) -> None: + """Set up before first test method.""" + # Initialize the ROS context for the test node + rclpy.init() + + @classmethod + def tearDownClass(cls) -> None: + """Tear down after last test method.""" + # Shutdown the ROS context + rclpy.shutdown() + + def setUp(self) -> None: + """Set up before each test method.""" + # Create a ROS node for benchmark tests + self.node = rclpy.create_node('Controller', namespace=self.generate_namespace()) + + def tearDown(self) -> None: + """Tear down after each test method.""" + self.node.destroy_node() + + @classmethod + def generate_namespace(cls, *tokens: Iterable[str], absolute=True) -> str: + """ + Generate a namespace with an optional list of tokens. + + This function is a utility for producing namespaced topic and service names in + such a way that there are no collisions between 'dummy' nodes running for testing + and 'normal' nodes running on the same machine. + + Parameters + ---------- + tokens : Iterable[str] + List of tokens to include in the namespace. Often used to generate + separate namespaces for Isaac ROS and reference implementations. + + absolute: bool + Whether or not to generate an absolute namespace, by default True. + + Returns + ------- + str + The generated namespace as a slash-delimited string + + """ + return ('/' if absolute else '') + '/'.join( + filter(None, [cls.config.benchmark_namespace, *tokens])) + + @staticmethod + def generate_test_description( + nodes: Iterable[launch.Action], node_startup_delay: float = 5.0 + ) -> launch.LaunchDescription: + """ + Generate a test launch description. + + The nodes included in this launch description will be launched as a test fixture + immediately before the first test in the test class runs. Note that the graph is + NOT shut down or re-launched between tests within the same class. + + Parameters + ---------- + nodes : Iterable[launch.Action] + List of Actions to launch before running the test. + node_startup_delay : float, optional + Seconds to delay by to account for node startup, by default 2.0 + + Returns + ------- + launch.LaunchDescription + The LaunchDescription object to launch before running the test + + """ + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=node_startup_delay, actions=[launch_testing.actions.ReadyToTest()]) + ] + ) + + @staticmethod + def generate_test_description_with_nsys( + launch_setup, node_startup_delay: float = 5.0 + ) -> launch.LaunchDescription: + """Generate a test launch description with the nsys capability built in.""" + launch_args = NsysUtility.generate_launch_args() + bound_launch_setup = partial( + NsysUtility.launch_setup_wrapper, + launch_setup=launch_setup) + nodes = launch_args + [OpaqueFunction(function=bound_launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=node_startup_delay, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) + + def get_logger(self, child_name=''): + """Get logger with child layers.""" + if hasattr(self, 'node'): + base_logger = self.node.get_logger() + else: + base_logger = rclpy.logging.get_logger('ROS2BenchmarkTest') + + if child_name: + return base_logger.get_child(child_name) + + if len(self._logger_name_stack) == 0: + return base_logger + + for logger_name in self._logger_name_stack: + if logger_name: + base_logger = base_logger.get_child(logger_name) + + return base_logger + + def push_logger_name(self, name): + """Add a child layer to the logger.""" + self._logger_name_stack.append(name) + + def pop_logger_name(self): + """Pop a child layer from the logger.""" + self._logger_name_stack.pop() + + def override_config_from_env(self): + """Override config parameters with values from environment variables.""" + override_config_dict = {} + for param_key in self.config.__dict__.keys(): + env_value = os.getenv(f'ROS2_BENCHMARK_OVERRIDE_{param_key.upper()}') + if env_value is not None: + override_config_dict[param_key] = env_value + self.get_logger().info( + f'Updating a benchmark config from env: {param_key} = {env_value}') + self.config.apply_to_attributes(override_config_dict) + + @classmethod + def get_assets_root_path(cls): + """Get assets path provided in configurations.""" + return cls.config.assets_root + + def get_input_data_absolute_path(self): + """Construct the absolute path of the input data file from configurations.""" + return os.path.join(self.config.assets_root, self.config.input_data_path) + + def print_report(self, report: dict, sub_heading: str = '') -> None: + """Print the given report.""" + heading = self.config.benchmark_name + + # Temporarily remove configs from the report as we don't want it to be printed + config_value = None + if 'metadata' in report: + config_value = report['metadata'].pop(BenchmarkMetadata.CONFIG, None) + + is_prev_dict = False + table_blocks = [] + table_block_rows = [] + + def construct_table_blocks_helper(prefix, data): + nonlocal is_prev_dict + nonlocal table_blocks + nonlocal table_block_rows + for key, value in data.items(): + key_str = str(key.value) if isinstance(key, Enum) else str(key) + if isinstance(value, dict): + if not is_prev_dict and len(table_block_rows) > 0: + table_blocks.append(table_block_rows) + table_block_rows = [] + is_prev_dict = True + construct_table_blocks_helper(f'{prefix}[{key_str}] ', value) + if not is_prev_dict: + table_blocks.append(table_block_rows) + table_block_rows = [] + is_prev_dict = True + elif isinstance(value, Enum): + table_block_rows.append(f'{prefix}{key_str} : {value.value}') + is_prev_dict = False + elif isinstance(value, float): + table_block_rows.append(f'{prefix}{key_str} : {"{:.3f}".format(value)}') + is_prev_dict = False + else: + table_block_rows.append(f'{prefix}{key_str} : {value}') + is_prev_dict = False + + construct_table_blocks_helper('', report) + if len(table_block_rows) > 0: + table_blocks.append(table_block_rows) + max_row_width = max([len(row) for rows in table_blocks for row in rows] + + [len(heading), len(sub_heading)]) + max_row_width = min(max_row_width, MAX_REPORT_OUTPUT_WIDTH) + + def print_line_helper(): + self.get_logger().info('+-{}-+'.format('-'*max_row_width)) + + def print_row_helper(row): + self.get_logger().info('| {:<{width}} |'.format(row, width=max_row_width)) + + def print_table_helper(): + print_line_helper() + self.get_logger().info('| {:^{width}} |'.format(heading, width=max_row_width)) + if sub_heading: + self.get_logger().info('| {:^{width}} |'.format(sub_heading, width=max_row_width)) + print_line_helper() + for rows in table_blocks: + for row in rows: + print_row_helper(row) + print_line_helper() + + print_table_helper() + + if config_value is not None: + report['metadata'][BenchmarkMetadata.CONFIG] = config_value + + def construct_final_report(self, report: dict) -> dict: + """Construct and return the final report from the given report.""" + final_report = report + + if len(self.config.custom_report_info) > 0: + final_report['custom'] = self.config.custom_report_info + + # Add benchmark metadata + metadata = {} + + # Benchmark launch info + metadata[BenchmarkMetadata.NAME] = self.config.benchmark_name + metadata[BenchmarkMetadata.TEST_FILE_PATH] = self._test_file_path + metadata[BenchmarkMetadata.TEST_DATETIME] = \ + self._test_datetime.strftime('%Y-%m-%dT%H:%M:%SZ') + + # Systeme info + uname = platform.uname() + metadata[BenchmarkMetadata.DEVICE_HOSTNAME] = uname.node + metadata[BenchmarkMetadata.DEVICE_ARCH] = uname.machine + metadata[BenchmarkMetadata.DEVICE_OS] = \ + f'{uname.system} {uname.release} {uname.version}' + metadata[BenchmarkMetadata.CONFIG] = self.config.to_yaml_str() + + # Benchmark data info + metadata[BenchmarkMetadata.BENCHMARK_MODE] = self.config.benchmark_mode.value + if self.config.benchmark_mode in [BenchmarkMode.LOOPING, BenchmarkMode.SWEEPING]: + metadata[BenchmarkMetadata.PEAK_THROUGHPUT_PREDICTION] = \ + self._peak_throughput_prediction + metadata[BenchmarkMetadata.INPUT_DATA_PATH] = self.get_input_data_absolute_path() + metadata[BenchmarkMetadata.INPUT_DATA_SIZE] = self._input_data_size_bytes + metadata[BenchmarkMetadata.INPUT_DATA_HASH] = self._input_data_hash + if self.config.input_data_start_time != -1: + metadata[BenchmarkMetadata.INPUT_DATA_START_TIME] = \ + self.config.input_data_start_time + if self.config.input_data_end_time != -1: + metadata[BenchmarkMetadata.INPUT_DATA_END_TIME] = \ + self.config.input_data_end_time + + final_report['metadata'] = metadata + + return final_report + + def export_report(self, report: dict) -> None: + """Export the given report to a JSON file.""" + + def to_json_compatible_helper(data): + data_out = {} + for key, value in data.items(): + if isinstance(value, dict): + data_out[str(key)] = to_json_compatible_helper(value) + elif isinstance(value, Enum): + data_out[str(key)] = str(value) + else: + try: + json.dumps(value) + data_out[str(key)] = value + except TypeError: + data_out[str(key)] = str(value) + return data_out + + if self.config.log_file_name == '': + timestr = self._test_datetime.strftime('%Y%m%d-%H%M%S') + log_file_path = os.path.join(self.config.log_folder, f'r2b-log-{timestr}.json') + else: + log_file_path = os.path.join(self.config.log_folder, self.config.log_file_name) + + with open(log_file_path, 'a') as f: + f.write(json.dumps(to_json_compatible_helper(report))) + self.get_logger().info(f'Exported benchmark report to {log_file_path}') + + def create_service_client_blocking(self, service_type, service_name): + """Create a service client and wait for it to be available.""" + namespaced_service_name = self.generate_namespace(service_name) + service_client = ClientUtility.create_service_client_blocking( + self.node, service_type, namespaced_service_name, + self.config.setup_service_client_timeout_sec) + if not service_client: + self.fail(f'Failed to create a {service_name} service client') + return service_client + + def get_service_response_from_future_blocking( + self, + future, + check_success=False, + timeout_sec=None): + """Block and wait for a service future to return.""" + if timeout_sec is None: + timeout_sec = self.config.default_service_future_timeout_sec + future_result = ClientUtility.get_service_response_from_future_blocking( + self.node, future, timeout_sec) + if not future_result: + self.fail('Failed to wait for a service future') + if check_success and not future_result.success: + self.fail('A service returned with an unsuccess response') + return future_result + + def prepare_buffer(self): + """Load data from a data loader node to a playback node.""" + self.push_logger_name('Loading') + + # Check the input data file + input_data_path = self.get_input_data_absolute_path() + try: + rosbag_info = rosbag2_py.Info() + rosbag_metadata = rosbag_info.read_metadata(input_data_path, 'sqlite3') + rosbag_file_path = input_data_path + if len(rosbag_metadata.files) > 0: + rosbag_file_path = os.path.join(input_data_path, rosbag_metadata.files[0].path) + elif len(rosbag_metadata.relative_file_paths) > 0: + rosbag_file_path = os.path.join( + input_data_path, rosbag_metadata.relative_file_paths[0]) + self.get_logger().info('Checking input data file...') + self.get_logger().info(f' - Rosbag path = {rosbag_file_path}') + if rosbag_metadata.compression_mode: + self.get_logger().info( + f' - Compression mode = {rosbag_metadata.compression_mode}') + if rosbag_metadata.compression_format: + self.get_logger().info( + f' - Compression format = {rosbag_metadata.compression_format}') + self.get_logger().info('Computing input data file hash...') + hash_md5 = hashlib.md5() + self._input_data_size_bytes = 0 + with open(rosbag_file_path, 'rb') as input_data: + while True: + next_chunk = input_data.read(4096) + self._input_data_size_bytes += len(next_chunk) + if next_chunk == b'': + break + hash_md5.update(next_chunk) + self._input_data_hash = hash_md5.hexdigest() + self.get_logger().info(f' - File hash = "{self._input_data_hash}"') + self.get_logger().info(f' - File size (bytes) = {self._input_data_size_bytes}') + except FileNotFoundError: + self.fail(f'Could not open the input data file at "{input_data_path}"') + + # Create service clients + set_data_client = self.create_service_client_blocking( + SetData, 'set_data') + start_loading_client = self.create_service_client_blocking( + StartLoading, 'start_loading') + stop_loading_client = self.create_service_client_blocking( + StopLoading, 'stop_loading') + start_recording_client = self.create_service_client_blocking( + StartRecording, 'start_recording') + + # Set and initialize data + self.get_logger().info('Requesting to initialize the data loader node') + set_data_request = SetData.Request() + set_data_request.data_path = input_data_path + set_data_request.publish_tf_messages = self.config.publish_tf_messages_in_set_data + set_data_request.publish_tf_static_messages = \ + self.config.publish_tf_static_messages_in_set_data + set_data_future = set_data_client.call_async(set_data_request) + self.get_service_response_from_future_blocking( + set_data_future, + check_success=True, + timeout_sec=self.config.set_data_service_future_timeout_sec) + + # Start recording + self.get_logger().info('Requesting to record messages.') + start_recording_request = StartRecording.Request() + start_recording_request.buffer_length = self.config.playback_message_buffer_size + start_recording_request.timeout = self.config.start_recording_service_timeout_sec + start_recording_request.record_data_timeline = self.config.record_data_timeline + if self.config.benchmark_mode == BenchmarkMode.TIMELINE: + self.get_logger().info('Requesting to get topic message timestamps.') + start_recording_request.topic_message_timestamps = self.get_topic_message_timestamps() + start_recording_future = start_recording_client.call_async(start_recording_request) + + # Load and play messages from the data loader node + self.get_logger().info('Requesting to load messages.') + start_loading_request = StartLoading.Request() + start_loading_request.publish_in_real_time = self.config.load_data_in_real_time + if self.config.input_data_start_time != -1: + start_loading_request.start_time_offset_ns = \ + int(self.config.input_data_start_time * (10**9)) + if self.config.input_data_end_time != -1: + start_loading_request.end_time_offset_ns = \ + int(self.config.input_data_end_time * (10**9)) + if self.config.benchmark_mode == BenchmarkMode.TIMELINE: + start_loading_request.repeat_data = False + else: + start_loading_request.repeat_data = True + start_loading_future = start_loading_client.call_async( + start_loading_request) + + # Wait for the recording request to finish (or time out) + self.get_logger().info('Waiting for the recording service to end.') + start_recording_response = self.get_service_response_from_future_blocking( + start_recording_future, + timeout_sec=self.config.start_recording_service_future_timeout_sec) + recorded_topic_message_counts = start_recording_response.recorded_topic_message_counts + recorded_message_count = start_recording_response.recorded_message_count + + # Stop loading data + self.get_logger().info('Requesting to stop loading data.') + stop_loading_request = StopLoading.Request() + stop_loading_future = stop_loading_client.call_async(stop_loading_request) + self.get_service_response_from_future_blocking(stop_loading_future) + + # Wait for data loader service (start_loading) to end + self.get_logger().info('Waiting for the start_loading serevice to end.') + self.get_service_response_from_future_blocking( + start_loading_future, check_success=True) + + self.assertTrue(recorded_message_count > 0, 'No message was recorded') + + if (not self.config.record_data_timeline): + for topic_message_count in recorded_topic_message_counts: + topic_name = topic_message_count.topic_name + recorded_count = topic_message_count.message_count + if self.config.benchmark_mode == BenchmarkMode.TIMELINE: + target_count = 0 + for topic_message_timestamps in \ + start_recording_request.topic_message_timestamps: + if topic_message_timestamps.topic_name == topic_name: + target_count = len(topic_message_timestamps.timestamps_ns) + break + else: + target_count = self.config.playback_message_buffer_size + self.assertTrue( + recorded_count >= target_count, + f'Not all messages were loaded ({topic_name}:{recorded_count}/{target_count})') + + self.get_logger().info( + f'All {recorded_message_count} messages were sucessfully recorded') + + self.pop_logger_name() + + def get_topic_message_timestamps(self): + """Get topic message timestamps from the service get_topic_message_timestamps.""" + get_topic_message_timestamps_client = self.create_service_client_blocking( + GetTopicMessageTimestamps, 'get_topic_message_timestamps') + get_topic_message_timestamps_request = GetTopicMessageTimestamps.Request() + if self.config.input_data_start_time != -1: + get_topic_message_timestamps_request.start_time_offset_ns = \ + int(self.config.input_data_start_time * (10**9)) + if self.config.input_data_end_time != -1: + get_topic_message_timestamps_request.end_time_offset_ns = \ + int(self.config.input_data_end_time * (10**9)) + get_topic_message_timestamps_future = get_topic_message_timestamps_client.call_async( + get_topic_message_timestamps_request) + get_topic_message_timestamps_response = self.get_service_response_from_future_blocking( + get_topic_message_timestamps_future, check_success=True) + return get_topic_message_timestamps_response.topic_message_timestamps + + def benchmark_body(self, playback_message_count, target_freq) -> dict: + """ + Run benchmark test. + + Parameters + ---------- + playback_message_count : + The number of messages to be tested + target_freq : + Target test publisher rate + + """ + # Create play_messages service + play_messages_client = self.create_service_client_blocking(PlayMessages, 'play_messages') + + # Create and send monitor service requests + monitor_service_client_map = {} + monitor_service_future_map = {} + for monitor_info in self.config.monitor_info_list: + # Create a monitor service client + start_monitoring_client = self.create_service_client_blocking( + StartMonitoring, monitor_info.service_name) + if start_monitoring_client is None: + return + + # Start monitoring messages + self.get_logger().info( + f'Requesting to monitor end messages from service "{monitor_info.service_name}".') + start_monitoring_request = StartMonitoring.Request() + start_monitoring_request.timeout = self.config.start_monitoring_service_timeout_sec + start_monitoring_request.message_count = playback_message_count + start_monitoring_request.revise_timestamps_as_message_ids = \ + self.config.revise_timestamps_as_message_ids + start_monitoring_future = start_monitoring_client.call_async( + start_monitoring_request) + + monitor_service_client_map[monitor_info.service_name] = start_monitoring_client + monitor_service_future_map[monitor_info.service_name] = start_monitoring_future + + # Start CPU profiler + if self.config.enable_cpu_profiler: + self._cpu_profiler.stop_profiling() + self._cpu_profiler.start_profiling(self.config.cpu_profiling_interval_sec) + self.get_logger().info('CPU profiling stared.') + + # Start playing messages + self.get_logger().info( + f'Requesting to play messages in playback_mode = {self.config.benchmark_mode}.') + play_messages_request = PlayMessages.Request() + play_messages_request.playback_mode = self.config.benchmark_mode.value + play_messages_request.target_publisher_rate = target_freq + play_messages_request.message_count = playback_message_count + play_messages_request.enforce_publisher_rate = self.config.enforce_publisher_rate + play_messages_request.revise_timestamps_as_message_ids = \ + self.config.revise_timestamps_as_message_ids + play_messages_future = play_messages_client.call_async(play_messages_request) + + # Watch playback node timeout + self.get_logger().info('Waiting for the playback service to finish.') + play_messages_response = self.get_service_response_from_future_blocking( + play_messages_future, + check_success=True, + timeout_sec=self.config.play_messages_service_future_timeout_sec) + + start_timestamps = {} + for i in range(len(play_messages_response.timestamps.keys)): + key = play_messages_response.timestamps.keys[i] + start_timestamp = play_messages_response.timestamps.timestamps_ns[i] + start_timestamps[key] = start_timestamp + + # Get end timestamps from all monitors + monitor_end_timestamps_map = {} + for monitor_info in self.config.monitor_info_list: + self.get_logger().info( + f'Waiting for the monitor service "{monitor_info.service_name}" to finish.') + monitor_response = self.get_service_response_from_future_blocking( + monitor_service_future_map[monitor_info.service_name]) + end_timestamps = {} + for i in range(len(monitor_response.timestamps.keys)): + key = monitor_response.timestamps.keys[i] + end_timestamp = monitor_response.timestamps.timestamps_ns[i] + end_timestamps[key] = end_timestamp + monitor_end_timestamps_map[monitor_info.service_name] = end_timestamps + + # Stop CPU profiler + if self.config.enable_cpu_profiler: + self._cpu_profiler.stop_profiling() + self.get_logger().info('CPU profiling stopped.') + + # Calculate performance results + performance_results = {} + for monitor_info in self.config.monitor_info_list: + end_timestamps = monitor_end_timestamps_map[monitor_info.service_name] + if len(end_timestamps) == 0: + error_message = 'No messages were observed from the monitor node ' + \ + monitor_info.service_name + self.get_logger().error(error_message) + raise RuntimeError(error_message) + for calculator in monitor_info.calculators: + performance_results.update( + calculator.calculate_performance(start_timestamps, end_timestamps)) + + # Add CPU profiler results + if self.config.enable_cpu_profiler: + performance_results.update(self._cpu_profiler.get_results()) + + return performance_results + + def determine_max_sustainable_framerate(self, test_func) -> float: + """ + Find the maximum sustainable test pulbisher framerate by using autotuner. + + Parameters + ---------- + test_func + The benchmark function to be tested + + Returns + ------- + float + The maximum sustainable test pulbisher framerate + + """ + self.push_logger_name('Probing') + + # Phase 1: Binary Search to identify interval + + current_upper_freq = self.config.publisher_upper_frequency + current_lower_freq = self.config.publisher_lower_frequency + + # Run a trial run to warm up the graph + try: + probe_freq = (current_upper_freq + current_lower_freq) / 2 + message_count = ceil( + self.config.benchmark_duration * + self.config.binary_search_duration_fraction * + probe_freq) + self.get_logger().info(f'Starting the trial probe at {probe_freq} Hz') + probe_perf_results = test_func(message_count, probe_freq) + self.print_report( + probe_perf_results, + sub_heading=f'Trial Probe {probe_freq}Hz') + except Exception: + self.get_logger().info( + f'Ignoring an exception occured in the trial probe at {probe_freq} Hz') + finally: + self.get_logger().info( + f'Finished the first trial probe at {probe_freq} Hz') + + # Continue binary search until the search window is small enough to justify a linear scan + while ( + abs(current_upper_freq - current_lower_freq) > + self.config.binary_search_terminal_interval_width + ): + probe_freq = (current_upper_freq + current_lower_freq) / 2 + self.get_logger().info( + f'Binary Search: Probing for max sustainable frequency at {probe_freq} Hz') + + # Perform mini-benchmark at this probe frequency + message_count = ceil( + self.config.benchmark_duration * + self.config.binary_search_duration_fraction * + probe_freq) + probe_perf_results = test_func(message_count, probe_freq) + self.print_report( + probe_perf_results, + sub_heading=f'Throughput Search Probe {probe_freq}Hz') + + # Check if this probe frequency was sustainable + first_monitor_perf = self.get_performance_results_of_first_monitor_calculator( + probe_perf_results) + if (first_monitor_perf[BasicPerformanceMetrics.MEAN_FRAME_RATE] >= + first_monitor_perf[BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE] - + self.config.binary_search_acceptable_frame_rate_drop + ) and ( + first_monitor_perf[BasicPerformanceMetrics.NUM_MISSED_FRAMES] <= + ceil(first_monitor_perf[BasicPerformanceMetrics.NUM_FRAMES_SENT] * + self.config.binary_search_acceptable_frame_loss_fraction) + ): + current_lower_freq = probe_freq + else: + current_upper_freq = probe_freq + + target_freq = current_lower_freq + + # Phase 2: Linear scan through interval from low to high + + # Increase probe frequency, until failures occur or ceiling is reached + while True: + probe_freq = target_freq + self.config.linear_scan_step_size + if probe_freq > self.config.publisher_upper_frequency: + break + + self.get_logger().info( + f'Linear Scan: Probing for max sustainable frequency at {probe_freq} Hz') + + # Perform mini-benchmark at this probe frequency + message_count = ceil( + self.config.benchmark_duration * + self.config.linear_scan_duration_fraction * + probe_freq) + probe_perf_results = test_func(message_count, probe_freq) + self.print_report( + probe_perf_results, + sub_heading=f'Throughput Search Probe {probe_freq}Hz') + + # Check if this probe frequency was sustainable + first_monitor_perf = self.get_performance_results_of_first_monitor_calculator( + probe_perf_results) + if (first_monitor_perf[BasicPerformanceMetrics.MEAN_FRAME_RATE] >= + first_monitor_perf[BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE] - + self.config.linear_scan_acceptable_frame_rate_drop + ) and ( + first_monitor_perf[BasicPerformanceMetrics.NUM_MISSED_FRAMES] <= + ceil(first_monitor_perf[BasicPerformanceMetrics.NUM_FRAMES_SENT] * + self.config.linear_scan_acceptable_frame_loss_fraction) + ): + target_freq = probe_freq + else: + # The new probe frequency is too high, so terminate the linear scan + break + + self.get_logger().info( + f'Final predicted max sustainable frequency was {target_freq}Hz') + + # Check if target frequency is at either lower or higher bound of range + BOUNDARY_LIMIT_EPSILON = 5 # (Hz) + if target_freq >= self.config.publisher_upper_frequency - BOUNDARY_LIMIT_EPSILON: + self.get_logger().warn( + f'Final playback framerate {target_freq} Hz is close to or above max framerate ' + f'{self.config.publisher_upper_frequency} Hz used in search window. ') + self.get_logger().warn( + 'Consider increasing this maximum!') + elif target_freq <= self.config.publisher_lower_frequency + BOUNDARY_LIMIT_EPSILON: + self.get_logger().warn( + f'Final playback framerate {target_freq} Hz is close to or below min framerate ' + f'{self.config.publisher_lower_frequency} Hz used in search window. ') + self.get_logger().warn( + 'Consider decreasing this minimum!') + + self.pop_logger_name() + return target_freq + + def pre_benchmark_hook(self): + """Override for benchamrk setup.""" + pass + + def post_benchmark_hook(self): + """Override for benchmark cleanup.""" + pass + + def run_benchmark(self): + """ + Run benchmarking. + + Entry method for running benchmark method self.benchmark_body() under various + benchmark modes. + """ + self.get_logger().info(f'Starting {self.config.benchmark_name} Benchmark') + + self.get_logger().info('Executing pre-benchmark setup') + self.pre_benchmark_hook() + + # Prepare playback buffers + if self.config.enable_trial_buffer_preparation: + self.push_logger_name('Trial') + self.get_logger().info('Starting trial message buffering') + self.prepare_buffer() + self.pop_logger_name() + self.get_logger().info('Buffering test messages') + self.prepare_buffer() + self.get_logger().info('Finished buffering test messages') + + self.get_logger().info(f'Running benchmark: mode={self.config.benchmark_mode}') + perf_results = {} + if self.config.benchmark_mode == BenchmarkMode.TIMELINE: + perf_results = self.run_benchmark_timeline_playback_mode() + elif (self.config.benchmark_mode == BenchmarkMode.LOOPING) or \ + (self.config.benchmark_mode == BenchmarkMode.SWEEPING): + perf_results = self.run_benchmark_looping_mode() + + final_report = self.construct_final_report(perf_results) + self.print_report(final_report, sub_heading='Final Report') + self.export_report(final_report) + + def run_benchmark_timeline_playback_mode(self) -> dict: + self.push_logger_name('Timeline') + playback_message_count = \ + int(self.config.benchmark_duration * self.config.publisher_upper_frequency) + perf_results = self.benchmark_body( + playback_message_count, + self.config.publisher_upper_frequency) + self.pop_logger_name() + return perf_results + + def run_benchmark_looping_mode(self) -> dict: + """ + Run benchmarking. + + This benchmark method aims to test the maximum output framerate for the + benchmark method self.benchmark_body(). + """ + self.push_logger_name('Looping') + + # Run Autotuner + self.get_logger().info('Running autotuner') + target_freq = self.determine_max_sustainable_framerate(self.benchmark_body) + self._peak_throughput_prediction = target_freq + self.get_logger().info( + 'Finished autotuning. ' + f'Running full-scale benchmark for predicted peak frame rate: {target_freq}') + + playback_message_count = int(self.config.benchmark_duration * target_freq) + + # Run benchmark iterations + self.reset_performance_calculators() + self._cpu_profiler.reset() + for i in range(self.config.test_iterations): + self.get_logger().info(f'Starting Iteration {i+1}') + performance_results = self.benchmark_body( + playback_message_count, + target_freq) + self.print_report(performance_results, sub_heading=f'{target_freq}Hz #{i+1}') + + # Conclude performance measurements from the iteratoins + final_perf_results = {} + for monitor_info in self.config.monitor_info_list: + for calculator in monitor_info.calculators: + final_perf_results.update(calculator.conclude_performance()) + # Conclude CPU profiler data + if self.config.enable_cpu_profiler: + final_perf_results.update(self._cpu_profiler.conclude_results()) + + # Run additional fixed rate test + self.push_logger_name('FixedRate') + additional_test_fixed_publisher_rates = \ + set(self.config.additional_fixed_publisher_rate_tests) + self.get_logger().info( + 'Starting fixed publisher rate tests for: ' + f'{additional_test_fixed_publisher_rates}') + for target_freq in additional_test_fixed_publisher_rates: + first_monitor_perf = self.get_performance_results_of_first_monitor_calculator( + final_perf_results) + mean_pub_fps = first_monitor_perf[BasicPerformanceMetrics.MEAN_PLAYBACK_FRAME_RATE] + if mean_pub_fps*1.05 < target_freq: + self.get_logger().info( + f'Skipped testing the fixed publisher rate for {target_freq}fps ' + 'as it is higher than the previously measured max sustainable ' + f'rate: {mean_pub_fps}') + continue + self.get_logger().info( + f'Testing fixed publisher rate at {target_freq}fps') + playback_message_count = int(self.config.benchmark_duration * target_freq) + performance_results = self.benchmark_body( + playback_message_count, + target_freq) + self.print_report(performance_results, sub_heading=f'Fixed {target_freq} FPS') + + # Add the test result to the output metrics + final_perf_results[f'{target_freq}fps'] = performance_results + + self.pop_logger_name() + return final_perf_results + + def get_performance_results_of_first_monitor_calculator(self, performance_results): + """Get dict that contains the first calculator's performance results.""" + calculator = self.config.monitor_info_list[0].calculators[0] + if 'report_prefix' in calculator.config and calculator.config['report_prefix']: + return performance_results[calculator.config['report_prefix']] + return performance_results + + def reset_performance_calculators(self): + """Reset the states of all performance calculators associated with all monitors.""" + for monitor_info in self.config.monitor_info_list: + for calculator in monitor_info.calculators: + calculator.reset() diff --git a/ros2_benchmark/ros2_benchmark/utils/__init__.py b/ros2_benchmark/ros2_benchmark/utils/__init__.py new file mode 100644 index 0000000..6bbcb13 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/ros2_benchmark/ros2_benchmark/utils/cpu_profiler.py b/ros2_benchmark/ros2_benchmark/utils/cpu_profiler.py new file mode 100644 index 0000000..e68b669 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/cpu_profiler.py @@ -0,0 +1,149 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +"""CPU profiler class to measure performance of benchmark tests.""" + +from enum import Enum +import numbers +from pathlib import Path +from threading import Thread + +import numpy as np +import psutil + +from .profiler import Profiler + + +class CPUProfilingMetrics(Enum): + """Metrics for CPU profiling.""" + + MAX_CPU_UTIL = 'Max. CPU Util. (%)' + MIN_CPU_UTIL = 'Min. CPU Util. (%)' + MEAN_CPU_UTIL = 'Mean CPU Util. (%)' + STD_DEV_CPU_UTIL = 'Std. Deviation CPU Util. (%)' + BASELINE_CPU_UTIL = 'Baseline CPU Util. (%)' + + +class CPUProfiler(Profiler): + """CPU profiler class to measure CPU performance of benchmark tests.""" + + def __init__(self): + """Construct CPU profiler.""" + super().__init__() + + def start_profiling(self, interval: float = 1.0) -> Path: + """ + Start CPU profiling thread to keep track of performance metrics. + + Parameters + ---------- + interval: float + The interval between measurements, in seconds + + """ + super().start_profiling() + + # While the is_running flag is true, log CPU usage + def psutil_log(): + with open(self._log_file_path, 'w+') as logfile: + while self._is_running: + logfile.write( + f'{psutil.cpu_percent(interval=interval, percpu=True)}\n') + + self.psutil_thread = Thread(target=psutil_log) + self.psutil_thread.start() + + return self._log_file_path + + def stop_profiling(self): + """Stop profiling.""" + if self._is_running: + super().stop_profiling() + # Wait for thread to stop + self.psutil_thread.join() + + def get_results(self, log_file_path=None) -> dict: + """Return CPU profiling results.""" + assert not self._is_running, 'Cannot collect results until profiler has been stopped!' + + log_file_path = self._log_file_path if log_file_path is None else log_file_path + assert self._log_file_path is not None, 'No log file for reading CPU profiling results.' + + profile_data = {} + with open(log_file_path) as logfile: + cpu_values = [] + for line in logfile.readlines(): + # Remove brackets from line before splitting entries by comma + cpu_values.append(np.mean([float(v) + for v in line[1:-2].split(',')])) + + cpu_values = np.array(cpu_values) + profile_data[CPUProfilingMetrics.MAX_CPU_UTIL] = np.max(cpu_values) + profile_data[CPUProfilingMetrics.MIN_CPU_UTIL] = np.min(cpu_values) + profile_data[CPUProfilingMetrics.MEAN_CPU_UTIL] = np.mean(cpu_values) + profile_data[CPUProfilingMetrics.STD_DEV_CPU_UTIL] = np.std(cpu_values) + profile_data[CPUProfilingMetrics.BASELINE_CPU_UTIL] = cpu_values[0] + + self._profile_data_list.append(profile_data) + + return profile_data + + def reset(self): + """Reset the profiler state.""" + self._profile_data_list.clear() + return + + def conclude_results(self) -> dict: + """Conclude final profiling outcome based on all previous results.""" + if len(self._profile_data_list) == 0: + self.get_logger().warn('No prior profile data to conclude') + return {} + + MEAN_METRICS = [ + CPUProfilingMetrics.MEAN_CPU_UTIL, + CPUProfilingMetrics.STD_DEV_CPU_UTIL, + CPUProfilingMetrics.BASELINE_CPU_UTIL + ] + MAX_METRICS = [ + CPUProfilingMetrics.MAX_CPU_UTIL + ] + MIN_METRICS = [ + CPUProfilingMetrics.MIN_CPU_UTIL + ] + + final_profile_data = {} + for metric in CPUProfilingMetrics: + metric_value_list = [profile_data.get(metric, None) for + profile_data in self._profile_data_list] + if not all([isinstance(value, numbers.Number) for value in metric_value_list]): + continue + + # Remove the best and the worst before concluding the metric + metric_value_list.remove(max(metric_value_list)) + metric_value_list.remove(min(metric_value_list)) + + if metric in MEAN_METRICS: + final_profile_data[metric] = sum(metric_value_list)/len(metric_value_list) + elif metric in MAX_METRICS: + final_profile_data[metric] = max(metric_value_list) + elif metric in MIN_METRICS: + final_profile_data[metric] = min(metric_value_list) + else: + final_profile_data[metric] = 'INVALID VALUES: NO CONCLUDED METHOD ASSIGNED' + + self.reset() + return final_profile_data diff --git a/ros2_benchmark/ros2_benchmark/utils/image_utility.py b/ros2_benchmark/ros2_benchmark/utils/image_utility.py new file mode 100644 index 0000000..5b78503 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/image_utility.py @@ -0,0 +1,57 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + + +class Resolution: + """Generic resolution vaule holder.""" + + def __init__(self, width, height, name=''): + """Initialize the resolution.""" + self._dict = {} + self._dict['width'] = int(width) + self._dict['height'] = int(height) + self._dict['name'] = name + + def __str__(self) -> str: + out_str = f'({self["width"]},{self["height"]})' + if self['name']: + out_str = f'{self["name"]} {out_str}' + return out_str + + def __setitem__(self, key, value): + self._dict[key] = value + + def __getitem__(self, key): + return self._dict[key] + + def __repr__(self): + return f'Resolution({self["width"]}, {self["height"]}, {self["name"]})' + + def yaml_representer(dumper, data): + """Support dumping a Resolution object in YAML.""" + return dumper.represent_scalar('tag:yaml.org,2002:str', repr(data)) + + +class ImageResolution: + """Common image resolutions.""" + + QUARTER_HD = Resolution(960, 540, 'Quarter HD') + VGA = Resolution(640, 480, 'VGA') + WVGA = Resolution(720, 480, 'WVGA') + HD = Resolution(1280, 720, 'HD') + FULL_HD = Resolution(1920, 1080, 'Full HD') + FOUR_K = Resolution(3840, 2160, '4K') diff --git a/ros2_benchmark/ros2_benchmark/utils/nsys_utility.py b/ros2_benchmark/ros2_benchmark/utils/nsys_utility.py new file mode 100644 index 0000000..07f3172 --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/nsys_utility.py @@ -0,0 +1,85 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import datetime +from inspect import signature +import platform + +from launch.actions import DeclareLaunchArgument +from launch.conditions import IfCondition +from launch.substitutions import LaunchConfiguration + + +class NsysUtility(): + """Utilities for enabling Nsight System profiling.""" + + @staticmethod + def generate_launch_args(): + """ + Generate launch args for nsight systme profiling. + + Usage Example: launch_test + enable_nsys:= + nsys_profile_name:= + nsys_profile_flags:= + """ + return [ + DeclareLaunchArgument('enable_nsys', default_value='false', + description='Enable nsys profiling'), + DeclareLaunchArgument('nsys_profile_name', default_value='', + description='Label to append for nsys profile output'), + DeclareLaunchArgument('nsys_profile_flags', default_value='--trace=osrt,nvtx,cuda', + description='Flags for nsys profile') + ] + + @staticmethod + def generate_nsys_prefix(context): + """Generate prefi for nsight systme profiling.""" + enable_nsys = IfCondition(LaunchConfiguration( + 'enable_nsys')).evaluate(context) + nsys_profile_name = LaunchConfiguration( + 'nsys_profile_name').perform(context) + nsys_profile_flags = LaunchConfiguration( + 'nsys_profile_flags').perform(context) + + container_prefix = '' + if enable_nsys: + if(not nsys_profile_name): + current_time = datetime.datetime.now(datetime.timezone.utc).\ + strftime('%Y-%m-%dT%H:%M:%SZ') + nsys_profile_name = f'profile_{platform.machine()}_{current_time}' + container_prefix = f'nsys profile {nsys_profile_flags} -o {nsys_profile_name}' + return (enable_nsys, container_prefix) + + @staticmethod + def launch_setup_wrapper(context, launch_setup): + """Invoke the launch_setup method with nsys parameters for ComposableNodeContainer.""" + enable_nsys, container_prefix = NsysUtility.generate_nsys_prefix(context) + launch_setup_parameters = signature(launch_setup).parameters + if (not all([param in launch_setup_parameters for param in + ['container_prefix', 'container_sigterm_timeout']])): + if enable_nsys: + raise RuntimeError( + 'Incorrect launch_setup signature. ' + 'When Nsys is enbaled, the signature must be: ' + 'def launch_setup(container_prefix, container_sigterm_timeout)') + else: + return launch_setup() + container_sigterm_timeout = '1000' if enable_nsys else '5' + return launch_setup( + container_prefix=container_prefix, + container_sigterm_timeout=container_sigterm_timeout) diff --git a/ros2_benchmark/ros2_benchmark/utils/profiler.py b/ros2_benchmark/ros2_benchmark/utils/profiler.py new file mode 100644 index 0000000..3a401af --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/profiler.py @@ -0,0 +1,82 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +"""Profiler base class to measure the performance of benchmark tests.""" + +from abc import ABC, abstractmethod +from datetime import datetime +import os + + +class Profiler(ABC): + """Profiler base class to measure the performance of benchmark tests.""" + + DEFAILT_LOG_DIR = '/tmp' + + @abstractmethod + def __init__(self): + """Construct profiler.""" + self._is_running = False + + # Logfile path is generated once start_profiling() is called + self._log_file_path = None + + self._profile_data_list = [] + + @abstractmethod + def start_profiling(self, log_dir=DEFAILT_LOG_DIR) -> None: + """ + Run profiling program to keep track of performance metrics. + + Parameters + ---------- + log_dir + Path to write the logs to + + """ + assert not self._is_running, 'Profiler has already been started!' + self._is_running = True + + # Create log file folders if they don't exist already + os.makedirs(log_dir, exist_ok=True) + + self._log_file_path = os.path.join( + log_dir, + f'{type(self).__name__}_{datetime.timestamp(datetime.now())}.log') + + return self._log_file_path + + @abstractmethod + def stop_profiling(self) -> None: + """Stop profiling.""" + self._is_running = False + + @abstractmethod + def get_results(self, log_file_path=None) -> dict: + """Return profiling results.""" + return {} + + @abstractmethod + def reset(self): + """Reset the profiler state.""" + self._profile_data_list.clear() + return + + @abstractmethod + def conclude_results(self) -> dict: + """Conclude final profiling outcome based on all previous results.""" + return {} diff --git a/ros2_benchmark/ros2_benchmark/utils/ros2_utility.py b/ros2_benchmark/ros2_benchmark/utils/ros2_utility.py new file mode 100644 index 0000000..db1a50d --- /dev/null +++ b/ros2_benchmark/ros2_benchmark/utils/ros2_utility.py @@ -0,0 +1,50 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import time + +import rclpy + + +class ClientUtility: + """A class for hosting utility methods for ROS 2 serevice clients.""" + + @staticmethod + def create_service_client_blocking(node, service_type, service_name, timeout_sec): + """Create a service client and wait for it to be available.""" + service_client = node.create_client(service_type, service_name) + start_time = time.time() + while not service_client.wait_for_service(timeout_sec=1): + node.get_logger().info( + f'{service_name} service is not available yet, waiting...') + if (time.time() - start_time) > timeout_sec: + node.get_logger().info( + f'Creating {service_name} service client timed out') + return None + return service_client + + @staticmethod + def get_service_response_from_future_blocking(node, future, timeout_sec): + """Block and wait for a service future to return.""" + start_time = time.time() + while not future.done(): + rclpy.spin_once(node) + if (time.time() - start_time) > timeout_sec: + node.get_logger().info( + f'Waiting for a service future timed out ({timeout_sec}s)') + return None + return future.result() diff --git a/ros2_benchmark/src/data_loader_node.cpp b/ros2_benchmark/src/data_loader_node.cpp new file mode 100644 index 0000000..613b35a --- /dev/null +++ b/ros2_benchmark/src/data_loader_node.cpp @@ -0,0 +1,405 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#include "ros2_benchmark/data_loader_node.hpp" + +#include +#include +#include + +#include "ros2_benchmark_interfaces/msg/topic_message_timestamp_array.hpp" + +namespace ros2_benchmark +{ + +DataLoaderNode::DataLoaderNode(const rclcpp::NodeOptions & options) +: rclcpp::Node("DataLoader", options), + service_callback_group_{create_callback_group(rclcpp::CallbackGroupType::Reentrant)}, + set_data_service_{ + create_service( + "set_data", + std::bind( + &DataLoaderNode::SetDataServiceCallback, + this, + std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + start_loading_service_{ + create_service( + "start_loading", + std::bind( + &DataLoaderNode::StartLoadingServiceCallback, + this, + std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + stop_loading_service_{ + create_service( + "stop_loading", + std::bind(&DataLoaderNode::StopLoadingServiceCallback, this, std::placeholders::_1, + std::placeholders::_2), rmw_qos_profile_default, service_callback_group_)}, + get_topic_message_timestamps_service_{ + create_service( + "get_topic_message_timestamps", + std::bind( + &DataLoaderNode::GetTopicMessageTimestampsSereviceCallback, + this, + std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + publisher_period_ms_(declare_parameter("publisher_period_ms", 10)) +{ +} + +void DataLoaderNode::SetDataServiceCallback( + const ros2_benchmark_interfaces::srv::SetData::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::SetData::Response::SharedPtr response) +{ + topic_message_timestamps_.clear(); + rosbag_path_ = request->data_path; + RCLCPP_INFO(get_logger(), "Set the rosbag file to be: %s", rosbag_path_.c_str()); + try { + OpenRosbagFile(); + } catch (const std::runtime_error & error) { + RCLCPP_ERROR(get_logger(), "Failed to open the rosbag: %s", error.what()); + response->success = false; + return; + } + if (is_rosbag_compressed_) { + RCLCPP_INFO(get_logger(), "Detected that the rosbag was zstd-message-compressed."); + } + + // Create Publishers + auto topics = rosbag_reader_.get_all_topics_and_types(); + for (const auto & topic : topics) { + if (publishers_.find(topic.name) != publishers_.end()) { + continue; + } + + // Create dedicated TF publishers if required + if ((request->publish_tf_messages && topic.name == "/tf") || + (request->publish_tf_static_messages && topic.name == "/tf_static")) + { + rclcpp::QoS tf_qos = kBufferQoS; + std::shared_ptr tf_pub = create_generic_publisher( + topic.name, + topic.type, + tf_qos.reliable().transient_local()); + tf_publishers_.insert(std::make_pair(topic.name, tf_pub)); + } + + // Use a relative topic name to create a publisher so namespace can be + // prepended correctly + const std::string relative_topic_name = + (topic.name[0] == '/') ? topic.name.substr(1) : topic.name; + std::shared_ptr pub = + create_generic_publisher(relative_topic_name, topic.type, kBufferQoS); + + publishers_.insert(std::make_pair(topic.name, pub)); + topic_message_timestamps_[pub->get_topic_name()] = {}; + + RCLCPP_INFO( + get_logger(), + "Created a publisher: topic=\"%s\", type=\"%s\"", + pub->get_topic_name(), topic.type.c_str()); + } + + // Store message timestamps for each topic + bool first_message = true; + while (rosbag_reader_.has_next()) { + std::shared_ptr message = + rosbag_reader_.read_next(); + + if (publishers_.count(message->topic_name) == 0) { + RCLCPP_ERROR( + get_logger(), + "Failed to find a publisher, topic=\"%s\"", + message->topic_name.c_str()); + continue; + } + + // Update the first timestamp value if needed + if (first_message) { + first_message = false; + first_timestamp_ns_ = message->time_stamp; + last_timestamp_ns_ = message->time_stamp; + } else { + if (message->time_stamp < first_timestamp_ns_) { + first_timestamp_ns_ = message->time_stamp; + } + if (message->time_stamp > last_timestamp_ns_) { + last_timestamp_ns_ = message->time_stamp; + } + } + + // Store the message's rosbag-recorded timestamp + const std::string remapped_topic_name = publishers_[message->topic_name]->get_topic_name(); + topic_message_timestamps_[remapped_topic_name].push_back(message->time_stamp); + + // Publish TF messages if required + if ((request->publish_tf_messages && message->topic_name == "/tf") || + (request->publish_tf_static_messages && message->topic_name == "/tf_static")) + { + PublishMessage(tf_publishers_[message->topic_name], message); + RCLCPP_INFO( + get_logger(), + "Published a TF message to topic=\"%s\"", + message->topic_name.c_str()); + } + } + + response->success = true; +} + +void DataLoaderNode::StartLoadingServiceCallback( + const ros2_benchmark_interfaces::srv::StartLoading::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::StartLoading::Response::SharedPtr response) +{ + played_message_count_ = 0; + stop_playing_ = false; + + int64_t true_start_time_ns = first_timestamp_ns_; + if (request->start_time_offset_ns >= 0) { + true_start_time_ns = first_timestamp_ns_ + request->start_time_offset_ns; + } + + int64_t true_end_time_ns = last_timestamp_ns_; + if (request->end_time_offset_ns >= 0) { + true_end_time_ns = first_timestamp_ns_ + request->end_time_offset_ns; + } + + if (topic_message_timestamps_.size() == 0) { + RCLCPP_ERROR( + get_logger().get_child("StartLoadingServiceCallback"), + "No rosbag file was successfully loaded. " + "A service request to \"set_data\" must be sent before start_loading service " + "can proceed."); + response->success = false; + return; + } + + // Read the rosbag file from the beginning + OpenRosbagFile(); + int64_t timestamp_offset = this->get_clock()->now().nanoseconds() - first_timestamp_ns_; + + // Publish messages at the configured frequency + while (true) { + { + // Check if it is requested to stop loading + std::lock_guard lock(stop_playing_mutex_); + if (stop_playing_) { + break; + } + } + + if (!rosbag_reader_.has_next()) { + if (!request->repeat_data) { + break; + } + // Repeat loading data if requestd + OpenRosbagFile(); + timestamp_offset = this->get_clock()->now().nanoseconds() - first_timestamp_ns_; + } + + std::shared_ptr message = + rosbag_reader_.read_next(); + + if (publishers_.count(message->topic_name) == 0) { + RCLCPP_ERROR( + get_logger(), + "[DataLoaderNode] Failed to find a publisher, topic=\"%s\"", + message->topic_name.c_str()); + stop_playing_ = true; + response->success = false; + return; + } + + if ((message->time_stamp < true_start_time_ns) || + (message->time_stamp > true_end_time_ns)) + { + continue; + } + + if (request->publish_in_real_time) { + while (true) { + rclcpp::Time now = this->get_clock()->now(); + int64_t diff_to_next_timestamp = + (message->time_stamp + timestamp_offset) - now.nanoseconds(); + if (diff_to_next_timestamp <= 0) { + break; + } + rclcpp::sleep_for(std::chrono::nanoseconds(diff_to_next_timestamp)); + } + } + + PublishMessage(publishers_[message->topic_name], message); + played_message_count_++; + + if (!request->publish_in_real_time) { + std::this_thread::sleep_for(std::chrono::milliseconds(publisher_period_ms_)); + } + } + rosbag_reader_.close(); + + { + std::lock_guard lock(stop_playing_mutex_); + stop_playing_ = true; + } + response->played_message_count = played_message_count_; + response->success = true; + + auto topic_message_timestamps_message_list = + CreateTopicMessageTimestampArrayMessageList(true_start_time_ns, true_end_time_ns); + response->topic_message_timestamps.insert( + response->topic_message_timestamps.end(), + topic_message_timestamps_message_list.begin(), + topic_message_timestamps_message_list.end()); +} + +void DataLoaderNode::StopLoadingServiceCallback( + const ros2_benchmark_interfaces::srv::StopLoading::Request::SharedPtr, + ros2_benchmark_interfaces::srv::StopLoading::Response::SharedPtr) +{ + std::lock_guard lock(stop_playing_mutex_); + stop_playing_ = true; +} + +void DataLoaderNode::GetTopicMessageTimestampsSereviceCallback( + const ros2_benchmark_interfaces::srv::GetTopicMessageTimestamps::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::GetTopicMessageTimestamps::Response::SharedPtr response) +{ + if (topic_message_timestamps_.size() == 0) { + RCLCPP_ERROR( + get_logger(), + "[DataLoaderNode] No topic timestamps were available"); + response->success = false; + return; + } + + int64_t true_start_time_ns = first_timestamp_ns_; + if (request->start_time_offset_ns >= 0) { + true_start_time_ns = first_timestamp_ns_ + request->start_time_offset_ns; + } + + int64_t true_end_time_ns = last_timestamp_ns_; + if (request->end_time_offset_ns >= 0) { + true_end_time_ns = first_timestamp_ns_ + request->end_time_offset_ns; + } + + auto topic_message_timestamps_message_list = + CreateTopicMessageTimestampArrayMessageList(true_start_time_ns, true_end_time_ns); + response->topic_message_timestamps.insert( + response->topic_message_timestamps.end(), + topic_message_timestamps_message_list.begin(), + topic_message_timestamps_message_list.end()); + response->success = true; +} + +std::vector FilterValuesByRange( + const std::vector & values, + const int64_t start, + const int64_t end) +{ + std::vector filtered; + for (const auto value : values) { + if (value >= start && value <= end) { + filtered.push_back(value); + } + } + return filtered; +} + +std::vector +DataLoaderNode::CreateTopicMessageTimestampArrayMessageList( + const int64_t start_time_ns, + const int64_t end_time_ns) +{ + std::vector message_list; + for (const auto & [topic_name, recorded_timestamps] : topic_message_timestamps_) { + ros2_benchmark_interfaces::msg::TopicMessageTimestampArray topic_timestamps{}; + topic_timestamps.topic_name = topic_name; + topic_timestamps.timestamps_ns = FilterValuesByRange( + recorded_timestamps, start_time_ns, end_time_ns); + message_list.push_back(topic_timestamps); + } + return message_list; +} + +void DataLoaderNode::OpenRosbagFile() +{ + rcpputils::fs::path rosbag_path(rosbag_path_); + if (!rosbag_path.exists()) { + std::stringstream error_msg; + error_msg << "Could not load a rosbag file. " + << "\"" << rosbag_path.string() + << "\" does not exist"; + RCLCPP_ERROR(get_logger(), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } + + rosbag2_storage::StorageOptions storage_options; + storage_options.uri = rosbag_path_; + storage_options.storage_id = "sqlite3"; + + rosbag2_cpp::ConverterOptions converter_options; + converter_options.input_serialization_format = "cdr"; + converter_options.output_serialization_format = "cdr"; + + rosbag_reader_.open(storage_options, converter_options); + + // Check the rosbag's compression formats + std::string compression_format = rosbag_reader_.get_metadata().compression_format; + transform( + compression_format.begin(), compression_format.end(), + compression_format.begin(), ::tolower); + + std::string compression_mode = rosbag_reader_.get_metadata().compression_mode; + transform( + compression_mode.begin(), compression_mode.end(), + compression_mode.begin(), ::tolower); + + if ((compression_format == "zstd") && (compression_mode == "message")) { + is_rosbag_compressed_ = true; + } else { + is_rosbag_compressed_ = false; + } +} + +void DataLoaderNode::PublishMessage( + std::shared_ptr publisher, + std::shared_ptr message) +{ + if (is_rosbag_compressed_) { + decompressor_.decompress_serialized_bag_message(message.get()); + } + publisher->publish(rclcpp::SerializedMessage(*message->serialized_data)); +} + + +DataLoaderNode::~DataLoaderNode() +{ + rosbag_reader_.close(); +} + +} // namespace ros2_benchmark + +// Register as a component +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(ros2_benchmark::DataLoaderNode) diff --git a/ros2_benchmark/src/monitor_node.cpp b/ros2_benchmark/src/monitor_node.cpp new file mode 100644 index 0000000..78ddc0d --- /dev/null +++ b/ros2_benchmark/src/monitor_node.cpp @@ -0,0 +1,164 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#include "ros2_benchmark/monitor_node.hpp" + +namespace ros2_benchmark +{ + +MonitorNode::MonitorNode( + const std::string & node_name, + const rclcpp::NodeOptions & options) +: rclcpp::Node(node_name, options), + monitor_index_((uint32_t)declare_parameter("monitor_index", 0)), + monitor_service_name_(kMonitorNodeServiceBaseName + std::to_string(monitor_index_)), + monitor_data_format_(declare_parameter("monitor_data_format", "")), + service_callback_group_{create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive)}, + start_monitoring_service_{ + create_service( + monitor_service_name_, + std::bind( + &MonitorNode::StartMonitoringServiceCallback, + this, + std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)} +{ +} + +MonitorNode::MonitorNode(const rclcpp::NodeOptions & options) +: MonitorNode("MonitorNode", options) +{ + RCLCPP_INFO( + get_logger(), + "[MonitorNode] Starting a monitor node with a service name \"%s\"", + monitor_service_name_.c_str()); + + // Create a monitor subscriber + CreateGenericTypeMonitorSubscriber(); +} + +void MonitorNode::CreateGenericTypeMonitorSubscriber() +{ + std::function)> + monitor_subscriber_callback = + std::bind( + &MonitorNode::GenericMonitorSubscriberCallback, + this, + std::placeholders::_1); + + monitor_sub_ = this->create_generic_subscription( + "output", // topic name + monitor_data_format_, // message type in the form of "package/type" + kQoS, + monitor_subscriber_callback); + + RCLCPP_INFO( + get_logger(), + "[MonitorNode] Created a generic type monitor subscriber: topic=\"%s\"", + monitor_sub_->get_topic_name()); +} + +void MonitorNode::GenericMonitorSubscriberCallback( + std::shared_ptr serialized_message_ptr) +{ + if (revise_timestamps_as_message_ids_) { + uint32_t end_timestamp = 0; + uint8_t * byte_ptr = reinterpret_cast(&end_timestamp); + *(byte_ptr + 0) = serialized_message_ptr->get_rcl_serialized_message().buffer[4]; + *(byte_ptr + 1) = serialized_message_ptr->get_rcl_serialized_message().buffer[5]; + *(byte_ptr + 2) = serialized_message_ptr->get_rcl_serialized_message().buffer[6]; + *(byte_ptr + 3) = serialized_message_ptr->get_rcl_serialized_message().buffer[7]; + // Here assumes the key is unique and identical to the second filed of timestamp + RecordEndTimestamp(end_timestamp); + } else { + RecordEndTimestampAutoKey(); + } +} + +bool MonitorNode::RecordEndTimestamp(const int32_t & message_key) +{ + // Record timestamp first, in case we need to wait to acquire mutex + const auto timestamp{std::chrono::system_clock::now()}; + + // If key already exists in end map, return false + if (end_timestamps_.count(message_key) > 0) { + RCLCPP_ERROR( + get_logger(), + "[MonitorNode] Message key %d existed when recording an end timestamp", + message_key); + return false; + } + + RCLCPP_DEBUG( + get_logger(), + "[MonitorNode] Recorded an end timestamp for message key %d", + message_key); + + // Add new entry to end timestamps + end_timestamps_.emplace(message_key, timestamp); + return true; +} + +bool MonitorNode::RecordEndTimestampAutoKey() +{ + return RecordEndTimestamp(end_timestamps_.size()); +} + +void MonitorNode::StartMonitoringServiceCallback( + const ros2_benchmark_interfaces::srv::StartMonitoring::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::StartMonitoring::Response::SharedPtr response) +{ + RCLCPP_DEBUG( + get_logger(), + "[MonitorNode] Enter monitor node callback"); + + revise_timestamps_as_message_ids_ = request->revise_timestamps_as_message_ids; + + // Initialize message for return + ros2_benchmark_interfaces::msg::TimestampedMessageArray timestamps{}; + + // Record start time for timeout checking + const auto start = std::chrono::system_clock::now(); + + // Assume messages keys are unique (may receive stale timestamps) + while ((end_timestamps_.size() < request->message_count) && + ((std::chrono::system_clock::now() - start) < std::chrono::seconds{request->timeout})) + { + std::this_thread::sleep_for(std::chrono::milliseconds(kThreadDelay)); + } + + // Record the keys of each message + for (auto it : end_timestamps_) { + timestamps.keys.emplace_back(it.first); + timestamps.timestamps_ns.emplace_back( + // Convert to nanoseconds + std::chrono::duration_cast( + it.second.time_since_epoch()).count()); + } + + response->timestamps = timestamps; + + end_timestamps_.clear(); +} + +} // namespace ros2_benchmark + +// Register as a component +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(ros2_benchmark::MonitorNode) diff --git a/ros2_benchmark/src/playback_node.cpp b/ros2_benchmark/src/playback_node.cpp new file mode 100644 index 0000000..748149d --- /dev/null +++ b/ros2_benchmark/src/playback_node.cpp @@ -0,0 +1,588 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#include "ros2_benchmark/playback_node.hpp" + +#include + +#include "ros2_benchmark_interfaces/msg/timestamped_message_array.hpp" +#include "ros2_benchmark_interfaces/msg/topic_message_count.hpp" + +using PlaybackMode = ros2_benchmark_interfaces::srv::PlayMessages::Request; + +namespace ros2_benchmark +{ + +std_msgs::msg::Header GenerateHeaderFromKey(int64_t key) +{ + std_msgs::msg::Header header{}; + + // Use the timestamp field to hold the unique, ordered key + header.stamp.sec = key; + return header; +} + +PlaybackNode::PlaybackNode( + const std::string & node_name, + const rclcpp::NodeOptions & options) +: rclcpp::Node(node_name, options), + service_callback_group_{create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive)}, + start_recording_service_{ + create_service( + "start_recording", + std::bind( + &PlaybackNode::StartRecordingServiceCallback, + this, std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + stop_recording_service_{ + create_service( + "stop_recording", + std::bind( + &PlaybackNode::StopRecordingServiceCallback, + this, std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + play_messages_service_{ + create_service( + "play_messages", + std::bind( + &PlaybackNode::PlayMessagesServiceCallback, + this, std::placeholders::_1, + std::placeholders::_2), + rmw_qos_profile_default, + service_callback_group_)}, + max_size_(std::numeric_limits::max()), + data_formats_(declare_parameter>( + "data_formats", + std::vector())), + timeline_topic_name_translations_( + declare_parameter>( + "timeline_topic_name_translations", + std::vector())) +{ +} + +PlaybackNode::PlaybackNode(const rclcpp::NodeOptions & options) +: PlaybackNode("PlaybackNode", options) +{ + if (data_formats_.empty()) { + throw std::invalid_argument( + "Empty data_formats, " + "this needs to be set to match the data formats for the data to be buffered"); + } + + for (size_t index = 0; index < data_formats_.size(); index++) { + CreateGenericPubSub(data_formats_[index], index); + } +} + +void PlaybackNode::CreateGenericPubSub(const std::string data_format, const size_t index) +{ + // Create a generic publisher + std::shared_ptr pub = this->create_generic_publisher( + "input" + std::to_string(index), + data_format, + kQoS); + + generic_pubs_[index] = pub; + RCLCPP_INFO( + get_logger(), "Created a generic publisher: topic=\"%s\"", + pub->get_topic_name()); + + // Create a generic subscriber + std::function)> + generic_type_subscriber_callback = + std::bind( + &PlaybackNode::GenericTypeRecordingSubscriberCallback, + this, + std::placeholders::_1, + index); + + std::shared_ptr sub = this->create_generic_subscription( + "buffer/input" + std::to_string(index), // topic name + data_format, // message type in the form of "package/type" + kBufferQoS, + generic_type_subscriber_callback); + + subs_[index] = sub; + RCLCPP_INFO( + get_logger(), "Created a generic subscriber: topic=\"%s\"", + sub->get_topic_name()); + + // Create a serialized message buffer + serialized_msg_buffers_[index] = std::vector>(); +} + +bool PlaybackNode::AreBuffersFull() const +{ + if (record_data_timeline_) { + return false; + } + if (requested_buffer_length_ == 0) { + if ((timestamps_to_messages_map_.size() > 0) && + (GetRecordedMessageCount() == GetTimestampsToMessagesCount())) + { + return true; + } + return false; + } + for (const auto & buffer : serialized_msg_buffers_) { + if (buffer.second.size() < requested_buffer_length_) { + return false; + } + } + return true; +} + +void PlaybackNode::ClearBuffers() +{ + for (auto & buffer : serialized_msg_buffers_) { + buffer.second.clear(); + } + timestamps_to_messages_map_.clear(); +} + +uint64_t PlaybackNode::GetRecordedMessageCount() const +{ + uint64_t message_count = 0; + for (const auto & buffer : serialized_msg_buffers_) { + message_count += buffer.second.size(); + } + return message_count; +} + +uint64_t PlaybackNode::GetRecordedMessageCount(size_t pub_index) const +{ + return serialized_msg_buffers_.at(pub_index).size(); +} + +uint64_t PlaybackNode::GetTimestampsToMessagesCount() const +{ + uint64_t count = 0; + for (const auto & it : timestamps_to_messages_map_) { + count += it.second.size(); + } + return count; +} + +bool PlaybackNode::PublishMessage( + const size_t pub_index, + const size_t message_index, + const std::optional & header = std::nullopt) +{ + const size_t buffer_size = serialized_msg_buffers_[pub_index].size(); + if (message_index >= buffer_size) { + const std::string topic_name = generic_pubs_[pub_index]->get_topic_name(); + RCLCPP_ERROR( + get_logger(), + "Failed to publish message index %ld for topic %s. " \ + "Total recorded messages = %ld", + message_index, topic_name.c_str(), buffer_size); + return false; + } + + if (header) { + // Update the sec field in the serialized message + uint8_t * header_sec_ptr = + const_cast(reinterpret_cast(&header->stamp.sec)); + serialized_msg_buffers_[pub_index].at(message_index) + .get()->get_rcl_serialized_message().buffer[4] = *(header_sec_ptr); + serialized_msg_buffers_[pub_index].at(message_index) + .get()->get_rcl_serialized_message().buffer[5] = *(header_sec_ptr + 1); + serialized_msg_buffers_[pub_index].at(message_index) + .get()->get_rcl_serialized_message().buffer[6] = *(header_sec_ptr + 2); + serialized_msg_buffers_[pub_index].at(message_index) + .get()->get_rcl_serialized_message().buffer[7] = *(header_sec_ptr + 3); + } + + generic_pubs_[pub_index]->publish( + *serialized_msg_buffers_[pub_index].at(message_index).get()); + return true; +} + +void PlaybackNode::PublishGroupMessages( + size_t message_index, + const std_msgs::msg::Header & header) +{ + for (size_t pub_index = 0; pub_index < GetPublisherCount(); pub_index++) { + if (revise_timestamps_as_message_ids_) { + PublishMessage(pub_index, message_index, header); + } else { + PublishMessage(pub_index, message_index); + } + RCLCPP_DEBUG( + get_logger(), + "Publishing a serialized message: index=%ld, timestamp=%d", + message_index, header.stamp.sec); + } +} + +void PlaybackNode::GenericTypeRecordingSubscriberCallback( + std::shared_ptr serialized_message_ptr, + size_t buffer_index) +{ + if ((serialized_msg_buffers_[buffer_index].size() >= max_size_) || + (requested_buffer_length_ > 0 && + serialized_msg_buffers_[buffer_index].size() >= requested_buffer_length_)) + { + RCLCPP_DEBUG( + get_logger(), "Dropped a serialized message due to a full buffer"); + return; + } + // Add received serialized message to the buffer + serialized_msg_buffers_[buffer_index].push_back(serialized_message_ptr); + RCLCPP_DEBUG( + get_logger(), "Added a serialized message to the buffer (%ld/%ld)", + serialized_msg_buffers_[buffer_index].size(), requested_buffer_length_); + + if (record_data_timeline_) { + int64_t now_ns = this->get_clock()->now().nanoseconds(); + size_t message_index = serialized_msg_buffers_[buffer_index].size() - 1; + AddToTimestampsToMessagesMap(now_ns, buffer_index, message_index); + } +} + +void PlaybackNode::StartRecordingServiceCallback( + const ros2_benchmark_interfaces::srv::StartRecording::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::StartRecording::Response::SharedPtr response) +{ + RCLCPP_INFO(get_logger(), "start_recording service began"); + + stop_recording_ = false; + requested_buffer_length_ = static_cast(request->buffer_length); + record_data_timeline_ = request->record_data_timeline; + if (record_data_timeline_) { + RCLCPP_INFO(get_logger(), "Enabled timeline recording"); + } + ClearBuffers(); + + // Store topic message timestamps if provided (passed by the controller from a + // data loader nodee). + if (!record_data_timeline_ && request->topic_message_timestamps.size() > 0) { + for (const auto & topic_message_timestamps : request->topic_message_timestamps) { + const std::string topic_name = topic_message_timestamps.topic_name; + for (const auto & [sub_index, sub_ptr] : subs_) { + const std::string sub_topic_name = sub_ptr->get_topic_name(); + + // A topic translation is required if there are nodes between a data loader + // node and the current node as their topic names will not match + std::string sub_translated_topic_name = ""; + if (timeline_topic_name_translations_.size() > sub_index) { + sub_translated_topic_name = timeline_topic_name_translations_[sub_index]; + } + + if (sub_topic_name == topic_name || sub_translated_topic_name == topic_name) { + size_t message_index = 0; + for (const auto timestamp : topic_message_timestamps.timestamps_ns) { + AddToTimestampsToMessagesMap(timestamp, sub_index, message_index); + message_index++; + } + break; + } + } + RCLCPP_DEBUG( + get_logger(), + "No matching topic \"%s\" for storing its message timestamps", + topic_name.c_str()); + } + } + + // Wait for all messages being recorded or reaching timeout + const auto service_start_time = std::chrono::system_clock::now(); + bool has_timeout = false; + while (true) { + { + std::lock_guard lock(stop_recording_mutex_); + if (AreBuffersFull() || stop_recording_) { + response->success = true; + break; + } + } + auto current_time = std::chrono::system_clock::now(); + if (current_time - service_start_time >= std::chrono::seconds{request->timeout}) { + response->success = false; + has_timeout = true; + break; + } + + std::this_thread::sleep_for(std::chrono::milliseconds(kThreadDelay)); + } + + { + std::lock_guard lock(stop_recording_mutex_); + stop_recording_ = true; + } + + // Respond with the number of messages recorded in each topic + response->recorded_message_count = GetRecordedMessageCount(); + for (const auto & [sub_index, sub_ptr] : subs_) { + ros2_benchmark_interfaces::msg::TopicMessageCount topic_message_count{}; + topic_message_count.topic_name = sub_ptr->get_topic_name(); + topic_message_count.message_count = GetRecordedMessageCount(sub_index); + response->recorded_topic_message_counts.push_back(topic_message_count); + } + + if (!record_data_timeline_ && has_timeout) { + RCLCPP_ERROR( + get_logger(), + "start_recording service returned with a timeout (%ld meessages recorded)", + response->recorded_message_count); + } +} + +void PlaybackNode::StopRecordingServiceCallback( + const ros2_benchmark_interfaces::srv::StopRecording::Request::SharedPtr, + ros2_benchmark_interfaces::srv::StopRecording::Response::SharedPtr) +{ + std::lock_guard lock(stop_recording_mutex_); + stop_recording_ = true; +} + +void PlaybackNode::PlayMessagesServiceCallback( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response) +{ + revise_timestamps_as_message_ids_ = request->revise_timestamps_as_message_ids; + switch (request->playback_mode) { + case PlaybackMode::PLAYBACK_MODE_TIMELINE: + RCLCPP_INFO( + get_logger(), + "Playing messages in the timeline playback mode"); + PlayMessagesTimelinePlayback(request, response); + break; + default: + RCLCPP_INFO( + get_logger(), + "Playing messages in the looping/sweeping mode"); + PlayMessagesLoopingSweeping(request, response); + break; + } +} + +void PlaybackNode::PlayMessagesTimelinePlayback( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response) +{ + (void)request; + + if (timestamps_to_messages_map_.size() == 0) { + RCLCPP_ERROR( + get_logger(), + "Could not play messages in the timeline playback mode due to missing " \ + "message timestamp information"); + response->success = false; + return; + } + + RCLCPP_INFO( + get_logger(), + "Start playing %ld/%ld messages in the timeline playback mode", + GetRecordedMessageCount(), + GetTimestampsToMessagesCount()); + + rclcpp::Time initial_timestamp = this->get_clock()->now(); + int64_t timestamp_offset = + initial_timestamp.nanoseconds() - timestamps_to_messages_map_.begin()->first; + for (const auto & [next_timestamp, message_list] : timestamps_to_messages_map_) { + while (true) { + rclcpp::Time now = this->get_clock()->now(); + int64_t diff_to_next_timestamp = (next_timestamp + timestamp_offset) - now.nanoseconds(); + if (diff_to_next_timestamp > 0) { + rclcpp::sleep_for(std::chrono::nanoseconds(diff_to_next_timestamp)); + continue; + } + // Now it's time to publish messages. + for (const auto & pub_message_index_pair : message_list) { + size_t pub_index = pub_message_index_pair.first; + size_t message_index = pub_message_index_pair.second; + if (!PublishMessage(pub_index, message_index)) { + // This message was not published due to an error. + continue; + } + + // Using the current message count as a key for recording a start timestamp + auto key = message_counter_++; + if (!RecordStartTimestamp(key)) { + RCLCPP_ERROR(get_logger(), "Failed to add start timestamp for key %d", key); + response->success = false; + return; + } + } + break; + } + } + + // Respond with start timestamps (when messages were being sent) + ros2_benchmark_interfaces::msg::TimestampedMessageArray response_timestamps{}; + for (auto it : start_timestamps_) { + response_timestamps.keys.emplace_back(it.first); + response_timestamps.timestamps_ns.emplace_back( + std::chrono::duration_cast( + it.second.time_since_epoch()).count()); + } + response->timestamps = response_timestamps; + response->success = true; + + start_timestamps_.clear(); +} + +void PlaybackNode::PlayMessagesLoopingSweeping( + const ros2_benchmark_interfaces::srv::PlayMessages::Request::SharedPtr request, + ros2_benchmark_interfaces::srv::PlayMessages::Response::SharedPtr response) +{ + // First, confirm that the expected number of buffered messages was greater than 0, + // otherwise we have no messages to play + if (requested_buffer_length_ <= 0) { + RCLCPP_ERROR( + get_logger(), + "Could not play messages: buffer length was not greater than 0"); + response->success = false; + return; + } + + // Then, confirm that we have buffered the expected number of messages + if (!AreBuffersFull()) { + RCLCPP_ERROR( + get_logger(), + "Did not receive all %lu expected messages on each buffer before starting playback", + requested_buffer_length_); + response->success = false; + return; + } + + // Initialize message for return + ros2_benchmark_interfaces::msg::TimestampedMessageArray timestamps{}; + + // Initialize playback rate + rclcpp::Rate rate{request->target_publisher_rate}; + + // If requested message count was 0 or smaller, default to one pass through the buffer + size_t message_count = + (request->message_count > 0) ? request->message_count : requested_buffer_length_; + + // Publish requested number of messages by looping through buffer + bool is_publisher_rate_met = true; + for (size_t i = 0; i < message_count; ++i) { + // Generate identifying key for the message + auto key = message_counter_++; + + // Generate header using that key + auto header = GenerateHeaderFromKey(key); + + // Publish message with generated header + size_t message_index; + if (request->playback_mode == PlaybackMode::PLAYBACK_MODE_SWEEPING) { + if ((i / requested_buffer_length_) % 2 == 1) { + message_index = requested_buffer_length_ - (i % requested_buffer_length_) - 1; + } else { + message_index = i % requested_buffer_length_; + } + } else { + message_index = i % requested_buffer_length_; + } + PublishGroupMessages(message_index, header); + + if (!RecordStartTimestamp(key)) { + RCLCPP_ERROR(get_logger(), "Failed to store start a timestamp for key %d", key); + response->success = false; + return; + } + + // Delay according to requested playback rate + if (!rate.sleep()) { + if (is_publisher_rate_met) { + is_publisher_rate_met = false; + RCLCPP_WARN( + get_logger(), "Couldn't maintain the requested playback rate at %0.2fHz", + request->target_publisher_rate); + } + + // Abort if requested to enforce the target publish rate + if (request->enforce_publisher_rate) { + RCLCPP_WARN( + get_logger(), "Abort as to target store start a timestamp for key %d", key); + response->success = false; + return; + } + } + } + + // Record the keys of each message + for (auto it : start_timestamps_) { + timestamps.keys.emplace_back(it.first); + timestamps.timestamps_ns.emplace_back( + // Convert to nanoseconds + std::chrono::duration_cast( + it.second.time_since_epoch()).count()); + } + + // Finally, mark success as true + response->success = true; + response->timestamps = timestamps; + + start_timestamps_.clear(); +} + +bool PlaybackNode::RecordStartTimestamp(const int64_t & message_key) +{ + // Record timestamp first, in case we need to wait to acquire mutex + const auto timestamp{std::chrono::system_clock::now()}; + + // If key already exists in start map, return false + if (start_timestamps_.count(message_key) > 0) { + return false; + } + + // Add entry to start timestamps, marking as unmatched + start_timestamps_[message_key] = timestamp; + return true; +} + +void PlaybackNode::AddToTimestampsToMessagesMap( + uint64_t timestamp, + size_t pub_index, + size_t message_index) +{ + if (timestamps_to_messages_map_.count(timestamp) == 0) { + timestamps_to_messages_map_[timestamp] = {}; + } + timestamps_to_messages_map_[timestamp].push_back({pub_index, message_index}); +} + +size_t PlaybackNode::GetPublisherCount() const +{ + return generic_pubs_.size(); +} + +const std::vector +PlaybackNode::GetRecordedTopicNames() +{ + std::vector topic_names; + for (const auto & [sub_index, sub_ptr] : subs_) { + topic_names.push_back(sub_ptr->get_topic_name()); + } + return topic_names; +} + +} // namespace ros2_benchmark + +// Register as a component +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(ros2_benchmark::PlaybackNode) diff --git a/ros2_benchmark/test/data_loader_node_pol.py b/ros2_benchmark/test/data_loader_node_pol.py new file mode 100644 index 0000000..2924d66 --- /dev/null +++ b/ros2_benchmark/test/data_loader_node_pol.py @@ -0,0 +1,120 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import time +import unittest + +import launch +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions +import rclpy + +from ros2_benchmark.utils.ros2_utility import ClientUtility +from ros2_benchmark_interfaces.srv import SetData, StartLoading, StopLoading + +DIR_PATH = os.path.dirname(os.path.realpath(__file__)) +ROSBAG_PATH = os.path.join(DIR_PATH, 'pol.bag/pol.bag_0.db3') + + +def generate_test_description(): + """Initialize test nodes and generate test description.""" + data_loader_node = ComposableNode( + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + name='DataLoaderNode', + ) + + data_loader_container = ComposableNodeContainer( + package='rclcpp_components', + name='data_loader_container', + namespace='', + executable='component_container_mt', + composable_node_descriptions=[data_loader_node], + output='screen' + ) + + return launch.LaunchDescription([ + data_loader_container, + launch_testing.actions.ReadyToTest() + ]) + + +class TestDataLoaderNode(unittest.TestCase): + """An unit test class for DataLoaderNode.""" + + def test_data_loader_node_services(self): + """Test services hosted in DataLoaderNode.""" + SERVICE_SETUP_TIMEOUT_SEC = 5 + SERVICE_FUTURE_TIMEOUT_SEC = 25 + + # Create a test ROS node + rclpy.init() + node = rclpy.create_node('test_node') + + # Create a set_data service client + set_data_client = ClientUtility.create_service_client_blocking( + node, SetData, 'set_data', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(set_data_client) + + # Create a start_loading service client + start_loading_client = ClientUtility.create_service_client_blocking( + node, StartLoading, 'start_loading', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(start_loading_client) + + # Create a stop_loading service client + stop_loading_client = ClientUtility.create_service_client_blocking( + node, StopLoading, 'stop_loading', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(stop_loading_client) + + # Send a request to the set_data service + set_data_request = SetData.Request() + set_data_request.data_path = ROSBAG_PATH + set_data_future = set_data_client.call_async( + set_data_request) + + # Wait for the response from the start_recording service + set_data_response = ClientUtility.get_service_response_from_future_blocking( + node, set_data_future, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(set_data_response) + self.assertTrue(set_data_response.success) + + # Send a request to the start_loading service + start_loading_request = StartLoading.Request() + start_loading_future = start_loading_client.call_async( + start_loading_request) + + time.sleep(1) + + # Send a request to the stop_loading service + stop_loading_request = StopLoading.Request() + stop_loading_future = stop_loading_client.call_async( + stop_loading_request) + + # Wait for the response from the start_recording service + start_loading_response = ClientUtility.get_service_response_from_future_blocking( + node, start_loading_future, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(start_loading_response) + node.get_logger().info('Received response from the start_loading service:') + node.get_logger().info(str(start_loading_response)) + + # Wait for the response from the start_recording service + stop_loading_response = ClientUtility.get_service_response_from_future_blocking( + node, stop_loading_future, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(stop_loading_response) + node.get_logger().info('Received response from the stop_loading service.') diff --git a/ros2_benchmark/test/monitor_node_pol.py b/ros2_benchmark/test/monitor_node_pol.py new file mode 100644 index 0000000..7840078 --- /dev/null +++ b/ros2_benchmark/test/monitor_node_pol.py @@ -0,0 +1,130 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import unittest + +import launch +from launch.actions import ExecuteProcess +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions +import rclpy + +from ros2_benchmark.utils.ros2_utility import ClientUtility +from ros2_benchmark_interfaces.srv import StartMonitoring + + +def generate_test_description(): + """Initialize test nodes and generate test description.""" + dir_path = os.path.dirname(os.path.realpath(__file__)) + rosbag_path = os.path.join(dir_path, 'pol.bag') + + monitor_node0 = ComposableNode( + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + name='MonitorNode0', + parameters=[{ + 'monitor_data_format': 'sensor_msgs/msg/Image', + 'monitor_index': 0 + }], + remappings=[ + ('output', '/image'), + ], + ) + + monitor_node1 = ComposableNode( + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + name='MonitorNode1', + parameters=[{ + 'monitor_data_format': 'sensor_msgs/msg/CameraInfo', + 'monitor_index': 1 + }], + remappings=[ + ('output', '/camera_info'), + ], + ) + + monitor_container = ComposableNodeContainer( + package='rclcpp_components', + name='monitor_container', + namespace='', + executable='component_container_mt', + composable_node_descriptions=[monitor_node0, monitor_node1], + output='screen' + ) + + # Play rosbag for the monitor node to receive messages + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path], + output='screen') + + return launch.LaunchDescription([ + rosbag_play, + monitor_container, + launch_testing.actions.ReadyToTest() + ]) + + +class TestMonitorNode(unittest.TestCase): + """An unit test class for MonitorNode.""" + + def test_monitor_node_services(self): + """Test services hosted in MonitorNode.""" + SERVICE_SETUP_TIMEOUT_SEC = 5 + SERVICE_TIMEOUT_SEC = 20 + SERVICE_FUTURE_TIMEOUT_SEC = 25 + + # Create a test ROS node + rclpy.init() + node = rclpy.create_node('test_node') + + # Create a start_monitoring0 service client + start_monitoring_client0 = ClientUtility.create_service_client_blocking( + node, StartMonitoring, 'start_monitoring0', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(start_monitoring_client0) + + # Create a start_monitoring1 service client + start_monitoring_client1 = ClientUtility.create_service_client_blocking( + node, StartMonitoring, 'start_monitoring1', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(start_monitoring_client1) + + # Send a request to the start_monitoring0 service + start_monitoring_request = StartMonitoring.Request() + start_monitoring_request.timeout = SERVICE_TIMEOUT_SEC + start_monitoring_request.message_count = 1 + start_monitoring_future0 = start_monitoring_client0.call_async( + start_monitoring_request) + + # Send a request to the start_monitoring1 service + start_monitoring_future1 = start_monitoring_client1.call_async( + start_monitoring_request) + + # Wait for the response from the start_monitoring0 service + start_monitoring_response0 = ClientUtility.get_service_response_from_future_blocking( + node, start_monitoring_future0, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(start_monitoring_response0) + node.get_logger().info('Received response from the start_monitoring0 service:') + node.get_logger().info(str(start_monitoring_response0)) + + # Wait for the response from the start_monitoring1 service + start_monitoring_response1 = ClientUtility.get_service_response_from_future_blocking( + node, start_monitoring_future1, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(start_monitoring_response1) + node.get_logger().info('Received response from the start_monitoring1 service:') + node.get_logger().info(str(start_monitoring_response1)) diff --git a/ros2_benchmark/test/playback_node_pol.py b/ros2_benchmark/test/playback_node_pol.py new file mode 100644 index 0000000..56774ff --- /dev/null +++ b/ros2_benchmark/test/playback_node_pol.py @@ -0,0 +1,117 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import unittest + +import launch +from launch.actions import ExecuteProcess +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions +import rclpy + +from ros2_benchmark.utils.ros2_utility import ClientUtility +from ros2_benchmark_interfaces.srv import PlayMessages, StartRecording + + +def generate_test_description(): + """Initialize test nodes and generate test description.""" + dir_path = os.path.dirname(os.path.realpath(__file__)) + rosbag_path = os.path.join(dir_path, 'pol.bag') + + playback_node = ComposableNode( + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + name='PlaybackNode', + parameters=[{ + 'data_formats': ['sensor_msgs/msg/Image'], + }], + remappings=[ + ('buffer/input0', 'buffer/image'), + ('input0', '/image') + ], + ) + + playback_container = ComposableNodeContainer( + package='rclcpp_components', + name='playback_container', + namespace='', + executable='component_container_mt', + composable_node_descriptions=[playback_node], + output='screen' + ) + + # Play rosbag for the playback node to record messages + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path, '--remap', 'image:=/buffer/image'], + output='screen') + + return launch.LaunchDescription([ + rosbag_play, + playback_container, + launch_testing.actions.ReadyToTest() + ]) + + +class TestPlaybackNode(unittest.TestCase): + """An unit test class for PlaybackNode.""" + + def test_playback_node_services(self): + """Test services hosted in PlaybackNode.""" + SERVICE_SETUP_TIMEOUT_SEC = 5 + SERVICE_TIMEOUT_SEC = 20 + SERVICE_FUTURE_TIMEOUT_SEC = 25 + + # Create a test ROS node + rclpy.init() + node = rclpy.create_node('test_node') + + # Create a start_recording service client + start_recording_client = ClientUtility.create_service_client_blocking( + node, StartRecording, 'start_recording', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(start_recording_client) + + # Create a play_messages service client + play_messages_client = ClientUtility.create_service_client_blocking( + node, PlayMessages, 'play_messages', SERVICE_SETUP_TIMEOUT_SEC) + self.assertIsNotNone(play_messages_client) + + # Send a request to the start_recording service + start_recording_request = StartRecording.Request() + start_recording_request.buffer_length = 10 + start_recording_request.timeout = SERVICE_TIMEOUT_SEC + start_recording_future = start_recording_client.call_async(start_recording_request) + + # Wait for the response from the start_recording service + start_recording_response = ClientUtility.get_service_response_from_future_blocking( + node, start_recording_future, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(start_recording_response) + node.get_logger().info('Received response from the start_recording service:') + node.get_logger().info(str(start_recording_response)) + + # Send a request to the play_messages service + play_messages_request = PlayMessages.Request() + play_messages_request.target_publisher_rate = 30.0 + play_messages_future = play_messages_client.call_async(play_messages_request) + + # Wait for the response from the play_messages service + play_messages_response = ClientUtility.get_service_response_from_future_blocking( + node, play_messages_future, SERVICE_FUTURE_TIMEOUT_SEC) + self.assertIsNotNone(play_messages_response) + node.get_logger().info('Received response from the play_messages service:') + node.get_logger().info(str(play_messages_response)) diff --git a/ros2_benchmark/test/pol.bag/metadata.yaml b/ros2_benchmark/test/pol.bag/metadata.yaml new file mode 100644 index 0000000..1c117bc --- /dev/null +++ b/ros2_benchmark/test/pol.bag/metadata.yaml @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:45eacd44a15f90b45f460198c1e83972c0933eae9426557bbd6d5c1c9d64d9a9 +size 1460 diff --git a/ros2_benchmark/test/pol.bag/pol.bag_0.db3 b/ros2_benchmark/test/pol.bag/pol.bag_0.db3 new file mode 100644 index 0000000..bdbead8 --- /dev/null +++ b/ros2_benchmark/test/pol.bag/pol.bag_0.db3 @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ff23a24fd7058446664b2e4a44a8f7ea597ee076dec9ce95f3aafaa67523a337 +size 220330308 diff --git a/ros2_benchmark/test/pol.bag/pol.bag_0.db3.zstd b/ros2_benchmark/test/pol.bag/pol.bag_0.db3.zstd new file mode 100644 index 0000000..ab39d69 --- /dev/null +++ b/ros2_benchmark/test/pol.bag/pol.bag_0.db3.zstd @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:3985838ccf2616632c07fc38a70c175e4380dad1f0d2bba862c4522d4a272519 +size 89565652 diff --git a/ros2_benchmark_interfaces/CMakeLists.txt b/ros2_benchmark_interfaces/CMakeLists.txt new file mode 100644 index 0000000..748cd7b --- /dev/null +++ b/ros2_benchmark_interfaces/CMakeLists.txt @@ -0,0 +1,64 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.5) +project(ros2_benchmark_interfaces) + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Default to Release build +if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE "Release" CACHE STRING "" FORCE) +endif() +message( STATUS "CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}" ) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +# Custom interfaces +find_package(rosidl_default_generators REQUIRED) +rosidl_generate_interfaces(${PROJECT_NAME} + msg/TimestampedMessageArray.msg + msg/TopicMessageCount.msg + msg/TopicMessageTimestampArray.msg + srv/GetTopicMessageTimestamps.srv + srv/PlayMessages.srv + srv/SetData.srv + srv/StartLoading.srv + srv/StartMonitoring.srv + srv/StartRecording.srv + srv/StopLoading.srv + srv/StopRecording.srv +) +ament_export_dependencies(rosidl_default_runtime) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + + ament_lint_auto_find_test_dependencies() + find_package(launch_testing_ament_cmake REQUIRED) +endif() + + +ament_auto_package() diff --git a/ros2_benchmark_interfaces/msg/TimestampedMessageArray.msg b/ros2_benchmark_interfaces/msg/TimestampedMessageArray.msg new file mode 100644 index 0000000..95c0a91 --- /dev/null +++ b/ros2_benchmark_interfaces/msg/TimestampedMessageArray.msg @@ -0,0 +1,25 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This message is used to provide message keys and timestamps. + +# An array of message keys +int64[] keys + +# An array of timestamps in (nanoseconds). The length should match +# the length of keys +int64[] timestamps_ns diff --git a/ros2_benchmark_interfaces/msg/TopicMessageCount.msg b/ros2_benchmark_interfaces/msg/TopicMessageCount.msg new file mode 100644 index 0000000..56c869d --- /dev/null +++ b/ros2_benchmark_interfaces/msg/TopicMessageCount.msg @@ -0,0 +1,24 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This message is used to provide the message count for a topic. + +# Topic name +string topic_name + +# Message count for the topic_name +uint64 message_count diff --git a/ros2_benchmark_interfaces/msg/TopicMessageTimestampArray.msg b/ros2_benchmark_interfaces/msg/TopicMessageTimestampArray.msg new file mode 100644 index 0000000..0367af5 --- /dev/null +++ b/ros2_benchmark_interfaces/msg/TopicMessageTimestampArray.msg @@ -0,0 +1,26 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This message is used to provide the message timeline for all the messages +# played from a rosbag for a topic. + +# Topic name +string topic_name + +# A list of message timestamps in nanoseconds corresponding to when each +# message should be published for this topic +int64[] timestamps_ns diff --git a/ros2_benchmark_interfaces/package.xml b/ros2_benchmark_interfaces/package.xml new file mode 100644 index 0000000..b9a244c --- /dev/null +++ b/ros2_benchmark_interfaces/package.xml @@ -0,0 +1,45 @@ + + + + + + + ros2_benchmark_interfaces + 0.30.0 + Interfaces for benchmark testing + + Hemal Shah + Apache-2.0 + https://developer.nvidia.com/isaac-ros-gems/ + CY Chen + Jaiveer Singh + Yuankun Zhu + + rosidl_default_generators + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + ament_cmake + + diff --git a/ros2_benchmark_interfaces/srv/GetTopicMessageTimestamps.srv b/ros2_benchmark_interfaces/srv/GetTopicMessageTimestamps.srv new file mode 100644 index 0000000..2660faf --- /dev/null +++ b/ros2_benchmark_interfaces/srv/GetTopicMessageTimestamps.srv @@ -0,0 +1,34 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service requests a data loader node to provide a timeline for +# when the messages load from a rosbag should be played for each topic. + +# Start time offset (in nanoseconds) of the data to be loaded +int64 start_time_offset_ns -1 + +# End time offset (in nanoseconds) of the data to be loaded +int64 end_time_offset_ns -1 + +--- + +# An array that holds the message playback timeline for each of the +# loaded topics +TopicMessageTimestampArray[] topic_message_timestamps + +# True if no error occured +bool success false diff --git a/ros2_benchmark_interfaces/srv/PlayMessages.srv b/ros2_benchmark_interfaces/srv/PlayMessages.srv new file mode 100644 index 0000000..fe04e0e --- /dev/null +++ b/ros2_benchmark_interfaces/srv/PlayMessages.srv @@ -0,0 +1,65 @@ +# This service requests a playback node to start playing messages after +# finished calling StartRecording.srv for buffering messages. + +# Definitions for playback modes +uint8 PLAYBACK_MODE_TIMELINE = 0 +uint8 PLAYBACK_MODE_LOOPING = 1 +uint8 PLAYBACK_MODE_SWEEPING = 2 + +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# Playback mode for how the buffered messages should be published +uint8 playback_mode 1 + +# The number of messages the buffer node should publish. +# Note that this does NOT need to be the same as the buffer_length (the +# number of the buffered messages) rquested in StartRecording.srv. The +# node will reuse and repeat messages if this value is smaller than +# buffer_length; otherwise omit as necessary in order to publish exactly +# the requested number of messages. +# A value of 0 or smaller defaults to publishing all buffered messages +# exactly once. +# It is ignored when the playback_mode is set to PLAYBACK_MODE_TIMELINE. +uint64 message_count 0 + +# The target rate, in hertz, to publish messages. A warning will be printed +# to the log console if the target rate cannot be maintained during the +# playback. +# It is ignored when the plackback_mode is set to PLAYBACK_MODE_TIMELINE. +float64 target_publisher_rate + +# Whether or not to stop and return an unsuccessful response if the target +# publish rate cannot be maintained. +bool enforce_publisher_rate false + +# Whether to use header.stamp.sec in each message's header as a message +# ID field +bool revise_timestamps_as_message_ids false + +--- + +# Whether or not playback proceeds successfully. Possible failures include: +# - Message timeline information is not available when using PLAYBACK_MODE_TIMELINE +# - Failed to store a message's publish timestamp due to duplicate message keys +# - Not all expected messages are present in the buffers before starting playback +# - Key duplication in buffered messages provided to the node +# - The target publisher rate cannot be met when enforce_publisher_rate is enabled +bool success false + +# The keys and timestamps of the messages that have been published +TimestampedMessageArray timestamps diff --git a/ros2_benchmark_interfaces/srv/SetData.srv b/ros2_benchmark_interfaces/srv/SetData.srv new file mode 100644 index 0000000..4218144 --- /dev/null +++ b/ros2_benchmark_interfaces/srv/SetData.srv @@ -0,0 +1,31 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service sets the path for the data file to be loaded in a data +# loader node. + +# Path to the data to be loaded +string data_path + +# Whether to publish /tf and /tf_static messages when setting up data +bool publish_tf_messages false +bool publish_tf_static_messages false + +--- + +# True if no error occured +bool success false diff --git a/ros2_benchmark_interfaces/srv/StartLoading.srv b/ros2_benchmark_interfaces/srv/StartLoading.srv new file mode 100644 index 0000000..89ceb5e --- /dev/null +++ b/ros2_benchmark_interfaces/srv/StartLoading.srv @@ -0,0 +1,45 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service requests a data loader node to start loading and +# publishing messages. It must be called after SetData.srv is called +# and finished. The service returns when receiving a StopLoading.srv +# service call. + +# Start time offset (in nanoseconds) of the data to be loaded +int64 start_time_offset_ns -1 + +# End time offset (in nanoseconds) of the data to be loaded +int64 end_time_offset_ns -1 + +# Whether to repeat loading data when the end is reached +bool repeat_data true + +# Whether to publish messages in real-time based on rosbag timestamps +bool publish_in_real_time false + +--- + +# An array that holds the message playback timeline for each of +# the loaded topics +TopicMessageTimestampArray[] topic_message_timestamps + +# The number of messages being sent +uint64 played_message_count 0 + +# True if no error occured before the service stopped +bool success false diff --git a/ros2_benchmark_interfaces/srv/StartMonitoring.srv b/ros2_benchmark_interfaces/srv/StartMonitoring.srv new file mode 100644 index 0000000..bac9054 --- /dev/null +++ b/ros2_benchmark_interfaces/srv/StartMonitoring.srv @@ -0,0 +1,36 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service requests a monitor node to start monitoring a +# topic's incoming messages. + +# The number of messages expected to be received during monitoring. +# The service returns early when all the expected messages are received. +uint64 message_count + +# Whether to use header.stamp.sec in each message's header as a message +# ID field +bool revise_timestamps_as_message_ids false + +# The maximum time, in seconds, to wait for receiving all expected +# messages. +int64 timeout + +--- + +# A list of message key-timestamp pairs for when the messages are received +TimestampedMessageArray timestamps diff --git a/ros2_benchmark_interfaces/srv/StartRecording.srv b/ros2_benchmark_interfaces/srv/StartRecording.srv new file mode 100644 index 0000000..a9eb167 --- /dev/null +++ b/ros2_benchmark_interfaces/srv/StartRecording.srv @@ -0,0 +1,46 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service is used to request a playback node to start recording +# incoming messages. + +# The number of messages to be buffered for each topic. +# All incoming messages will be buffered if set to 0. +uint64 buffer_length + +# The maximum time, in seconds, to wait for all expected number of +# messages to be buffereed +int64 timeout + +# An array that holds the message playback timeline for each topic. +# It must be provided if the timeline playback mode is to be used. +TopicMessageTimestampArray[] topic_message_timestamps + +# Enable recording message arrival timestamps and overriding +# topic_message_timestamps +bool record_data_timeline false + +--- + +# Whether or not all expected messages were received successfully +bool success false + +# The total number of messages being recorded +uint64 recorded_message_count + +# The number of messages recorded for each topic +TopicMessageCount[] recorded_topic_message_counts diff --git a/ros2_benchmark_interfaces/srv/StopLoading.srv b/ros2_benchmark_interfaces/srv/StopLoading.srv new file mode 100644 index 0000000..9010902 --- /dev/null +++ b/ros2_benchmark_interfaces/srv/StopLoading.srv @@ -0,0 +1,25 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service is for signaling a data loader node to stop an ongoing +# StartLoading.srv service that publish loaded messages. + +# No request fields + +--- + +# No response fields diff --git a/ros2_benchmark_interfaces/srv/StopRecording.srv b/ros2_benchmark_interfaces/srv/StopRecording.srv new file mode 100644 index 0000000..d371e83 --- /dev/null +++ b/ros2_benchmark_interfaces/srv/StopRecording.srv @@ -0,0 +1,25 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +# This service is for signaling a playback node to stop an ongoing +# StartRecording.srv service that records incoming messages. + +# No request fields + +--- + +# No response fields diff --git a/scripts/apriltag_ros_apriltag_graph.py b/scripts/apriltag_ros_apriltag_graph.py new file mode 100644 index 0000000..0d9cf1f --- /dev/null +++ b/scripts/apriltag_ros_apriltag_graph.py @@ -0,0 +1,168 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for apriltag_ros graph. + +The graph consists of the following: +- Preprocessors: + 1. PrepResizeNode: resizes images to HD +- Graph under Test: + 1. RectifyNode: rectifies images + 2. AprilTagNode: detects Apriltags + +Required: +- Packages: + - apriltag_ros +- Datasets: + - assets/datasets/r2b_dataset/r2b_storage +""" + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_storage' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking apriltag_ros graph.""" + + # Detector parameters to detect all 36h11 tags + cfg_36h11 = { + 'image_transport': 'raw', + 'family': '36h11', + 'size': 0.162 + } + + rectify_node = ComposableNode( + name='RectifyNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='image_proc', + plugin='image_proc::RectifyNode' + ) + + apriltag_node = ComposableNode( + name='AprilTagNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='apriltag_ros', + plugin='AprilTagNode', + parameters=[cfg_36h11], + remappings=[ + ('detections', 'apriltag_detections') + ] + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/camera_info')] + ) + + prep_resize_node = ComposableNode( + name='PrepResizeNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/image'), + ('image/camera_info', 'data_loader/camera_info'), + ('resize/image_raw', 'buffer/image'), + ('resize/camera_info', 'buffer/camera_info'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo'], + }], + remappings=[('buffer/input0', 'buffer/image'), + ('input0', 'image'), + ('buffer/input1', 'buffer/camera_info'), + ('input1', 'camera_info')], + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestAprilTagGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'apriltag_msgs/msg/AprilTagDetectionArray', + }], + remappings=[ + ('output', 'apriltag_detections')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestAprilTagGraph.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_resize_node, + playback_node, + monitor_node, + rectify_node, + apriltag_node + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestAprilTagGraph.generate_test_description_with_nsys(launch_setup) + +class TestAprilTagGraph(ROS2BenchmarkTest): + """Performance test for AprilTag graph.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='apriltag_ros AprilTag Graph Benchmark', + input_data_path=ROSBAG_PATH, + # The slice of the rosbag to use + input_data_start_time=3.0, + input_data_end_time=3.5, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=600.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=10, + custom_report_info={'data_resolution': IMAGE_RESOLUTION} + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/apriltag_ros_apriltag_node.py b/scripts/apriltag_ros_apriltag_node.py new file mode 100644 index 0000000..7333513 --- /dev/null +++ b/scripts/apriltag_ros_apriltag_node.py @@ -0,0 +1,164 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for apriltag_ros. + +The graph consists of the following: +- Preprocessors: + 1. PrepResizeNode: resizes images to HD +- Graph under Test: + 1. AprilTagNode: detects Apriltags + +Required: +- Packages: + - apriltag_ros +- Datasets: + - assets/datasets/r2b_dataset/r2b_storage +""" + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_storage' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking apriltag_ros.""" + + # Detector parameters to detect all 36h11 tags + cfg_36h11 = { + 'image_transport': 'raw', + 'family': '36h11', + 'size': 0.162 + } + + apriltag_node = ComposableNode( + name='AprilTagNode', + namespace=TestAprilTagNode.generate_namespace(), + package='apriltag_ros', + plugin='AprilTagNode', + parameters=[cfg_36h11], + remappings=[ + ('image_rect', 'image'), + ('detections', 'apriltag_detections') + ] + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestAprilTagNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/camera_info')] + ) + + prep_resize_node = ComposableNode( + name='PrepResizeNode', + namespace=TestAprilTagNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/image'), + ('image/camera_info', 'data_loader/camera_info'), + ('resize/image_raw', 'buffer/image'), + ('resize/camera_info', 'buffer/camera_info'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestAprilTagNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo' + ], + }], + remappings=[ + ('buffer/input0', 'buffer/image'), + ('input0', 'image'), + ('buffer/input1', 'buffer/camera_info'), + ('input1', 'camera_info') + ] + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestAprilTagNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'apriltag_msgs/msg/AprilTagDetectionArray', + }], + remappings=[ + ('output', 'apriltag_detections') + ] + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestAprilTagNode.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_resize_node, + playback_node, + monitor_node, + apriltag_node + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestAprilTagNode.generate_test_description_with_nsys(launch_setup) + +class TestAprilTagNode(ROS2BenchmarkTest): + """Performance test for AprilTagNode.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='apriltag_ros AprilTagNode Benchmark', + input_data_path=ROSBAG_PATH, + # The slice of the rosbag to use + input_data_start_time=3.0, + input_data_end_time=3.5, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=600.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=10, + custom_report_info={'data_resolution': IMAGE_RESOLUTION} + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/image_proc_rectify_node.py b/scripts/image_proc_rectify_node.py new file mode 100644 index 0000000..4561704 --- /dev/null +++ b/scripts/image_proc_rectify_node.py @@ -0,0 +1,147 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for image_proc RectifyNode. + +The graph consists of the following: +- Preprocessors: + None +- Graph under Test: + 1. RectifyNode: rectifies images + +Required: +- Packages: + - image_proc +- Datasets: + - assets/datasets/r2b_dataset/r2b_storage +""" + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_storage' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking image_proc RectifyNode.""" + + rectify_node = ComposableNode( + name='RectifyNode', + namespace=TestRectifyNode.generate_namespace(), + package='image_proc', + plugin='image_proc::RectifyNode', + remappings=[('image', 'image_raw')], + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestRectifyNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/camera_info')] + ) + + prep_resize_node = ComposableNode( + name='PrepResizeNode', + namespace=TestRectifyNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/image'), + ('image/camera_info', 'data_loader/camera_info'), + ('resize/image_raw', 'buffer/image'), + ('resize/camera_info', 'buffer/camera_info'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestRectifyNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo'], + }], + remappings=[('buffer/input0', 'buffer/image'), + ('input0', 'image_raw'), + ('buffer/input1', 'buffer/camera_info'), + ('input1', 'camera_info')], + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestRectifyNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'sensor_msgs/msg/Image', + }], + remappings=[ + ('output', 'image_rect')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestRectifyNode.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_resize_node, + playback_node, + monitor_node, + rectify_node + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestRectifyNode.generate_test_description_with_nsys(launch_setup) + + +class TestRectifyNode(ROS2BenchmarkTest): + """Performance test for image_proc RectifyNode.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='image_proc::RectifyNode Benchmark', + input_data_path=ROSBAG_PATH, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=2500.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=100, + custom_report_info={'data_resolution': IMAGE_RESOLUTION} + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/image_transport_h264_decoder_node.py b/scripts/image_transport_h264_decoder_node.py new file mode 100644 index 0000000..529c136 --- /dev/null +++ b/scripts/image_transport_h264_decoder_node.py @@ -0,0 +1,161 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for image_transport H264 decoder node. + +The graph consists of the following: +- Preprocessors: + 1. PrepResizeNode: resizes images to full HD + 2. PrepRepublishEncoderNode: encodes images to h264 +- Graph under Test: + 1. RepublishDecoderNode: decodes compressed images + +Required: +- Packages: + - ros2_h264_encoder + - h264_msgs + - h264_image_transport +- Datasets: + - assets/datasets/r2b_dataset/r2b_mezzanine +""" + +from launch_ros.actions import ComposableNodeContainer, Node +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.FULL_HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_mezzanine' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking image_transport decoder node.""" + + republish_node = Node( + name='RepublishDecoderNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='image_transport', + executable='republish', + arguments=['h264', 'raw', '--ros-args', '--log-level', 'error'], + remappings=[ + ('in/h264', 'compressed_image'), + ('out', 'image_uncompressed'), + ], + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/left_image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/left_camera_info')] + ) + + prep_resize_node = ComposableNode( + name='PrepResizeNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/left_image'), + ('image/camera_info', 'data_loader/left_camera_info'), + ('resize/image_raw', 'resized/image_raw'), + ('resize/camera_info', 'resized/camera_info'), + ] + ) + + prep_encoder_node = Node( + name='PrepRepublishEncoderNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='image_transport', + executable='republish', + arguments=['raw', 'h264'], + remappings=[ + ('in', 'resized/image_raw'), + ('out/h264', 'image_h264'), + ], + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'h264_msgs/msg/Packet'], + }], + remappings=[('buffer/input0', 'image_h264'), + ('input0', 'compressed_image')], + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestH264DecoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'sensor_msgs/msg/Image', + }], + remappings=[ + ('output', 'image_uncompressed')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestH264DecoderNode.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_resize_node, + playback_node, + monitor_node + ], + output='screen' + ) + + return [prep_encoder_node, republish_node, composable_node_container] + +def generate_test_description(): + return TestH264DecoderNode.generate_test_description_with_nsys(launch_setup) + + +class TestH264DecoderNode(ROS2BenchmarkTest): + """Performance test for image_transport H264 decoder node.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='image_transport H264 Decoder Node Benchmark', + input_data_path=ROSBAG_PATH, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=200.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=1 + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/image_transport_h264_encoder_node.py b/scripts/image_transport_h264_encoder_node.py new file mode 100644 index 0000000..5f871eb --- /dev/null +++ b/scripts/image_transport_h264_encoder_node.py @@ -0,0 +1,147 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for image_transport H264 encoder node. + +The graph consists of the following: +- Preprocessors: + 1. PrepResizeNode: resizes images to full HD +- Graph under Test: + 1. RepublishNode: encodes images to h264 + +Required: +- Packages: + - ros2_h264_encoder + - h264_msgs +- Datasets: + - assets/datasets/r2b_dataset/r2b_mezzanine +""" + +from launch_ros.actions import ComposableNodeContainer, Node +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.FULL_HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_mezzanine' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking image_transport H264 encoder node.""" + + republish_node = Node( + name='RepublishNode', + namespace=TestH264EncoderNode.generate_namespace(), + package='image_transport', + executable='republish', + arguments=['raw', 'h264'], + remappings=[ + ('in', 'image_raw'), + ('out/h264', 'image_h264'), + ], + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestH264EncoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/left_image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/left_camera_info')] + ) + + prep_resize_node = ComposableNode( + name='PrepResizeNode', + namespace=TestH264EncoderNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/left_image'), + ('image/camera_info', 'data_loader/left_camera_info'), + ('resize/image_raw', 'buffer/image_raw'), + ('resize/camera_info', 'buffer/camera_info'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestH264EncoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image'], + }], + remappings=[('buffer/input0', 'buffer/image_raw'), + ('input0', 'image_raw')] + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestH264EncoderNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'h264_msgs/msg/Packet', + }], + remappings=[ + ('output', 'image_h264')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestH264EncoderNode.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_resize_node, + playback_node, + monitor_node + ], + output='screen' + ) + + return [republish_node, composable_node_container] + +def generate_test_description(): + return TestH264EncoderNode.generate_test_description_with_nsys(launch_setup) + + +class TestH264EncoderNode(ROS2BenchmarkTest): + """Performance test for image_transport H264 encoder node.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='image_transport H264 Encoder Node Benchmark', + input_data_path=ROSBAG_PATH, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=200.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=100 + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/stereo_image_proc_graph.py b/scripts/stereo_image_proc_graph.py new file mode 100644 index 0000000..ebfb0b1 --- /dev/null +++ b/scripts/stereo_image_proc_graph.py @@ -0,0 +1,211 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for stereo_image_proc point cloud graph. + +The graph consists of the following: +- Preprocessors: + 1. PrepLeftResizeNode, PrepRightResizeNode: resizes images to quarter HD +- Graph under Test: + 1. DisparityNode: creates disparity images from stereo pair + 2. PointCloudNode: converts disparity to pointcloud + +Required: +- Packages: + - stereo_image_proc +- Datasets: + - assets/datasets/r2b_dataset/r2b_hideaway +""" + +import os + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.QUARTER_HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_hideaway' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking stereo_image_proc point cloud graph.""" + + env = os.environ.copy() + env['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE + # bare minimum formatting for console output matching + env['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}' + + disparity_node = ComposableNode( + name='DisparityNode', + namespace=TestStereoGraph.generate_namespace(), + package='stereo_image_proc', + plugin='stereo_image_proc::DisparityNode', + parameters=[{ + 'queue_size': 500, + 'approx': False, + 'use_system_default_qos': False + }], + remappings=[ + ('/left/camera_info', '/left/camera_info'), + ('/right/camera_info', '/right/camera_info'), + ('/left/image_rect', '/left/image_rect'), + ('/right/image_rect', '/right/image_rect')], + ) + + pointcloud_node = ComposableNode( + name='PointCloudNode', + namespace=TestStereoGraph.generate_namespace(), + package='stereo_image_proc', + plugin='stereo_image_proc::PointCloudNode', + parameters=[{ + 'approximate_sync': False, + 'avoid_point_cloud_padding': False, + 'use_color': False, + 'use_system_default_qos': False, + }], + remappings=[ + ('/left/camera_info', '/left/camera_info'), + ('/right/camera_info', '/right/camera_info'), + ('/left/image_rect', '/left/image_rect'), + ('/right/image_rect', '/right/image_rect'), + ('left/image_rect_color', 'left/image_rect')], + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestStereoGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/left_image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/left_camera_info'), + ('hawk_0_right_rgb_image', 'data_loader/right_image'), + ('hawk_0_right_rgb_camera_info', 'data_loader/right_camera_info')] + ) + + prep_left_resize_node = ComposableNode( + name='PrepLeftResizeNode', + namespace=TestStereoGraph.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/left_image'), + ('image/camera_info', 'data_loader/left_camera_info'), + ('resize/image_raw', 'buffer/left/image_resized'), + ('resize/camera_info', 'buffer/left/camera_info_resized'), + ] + ) + + prep_right_resize_node = ComposableNode( + name='PrepRightResizeNode', + namespace=TestStereoGraph.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/right_image'), + ('image/camera_info', 'data_loader/right_camera_info'), + ('resize/image_raw', 'buffer/right/image_resized'), + ('resize/camera_info', 'buffer/right/camera_info_resized'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestStereoGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo', + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo'], + }], + remappings=[('buffer/input0', 'buffer/left/image_resized'), + ('input0', 'left/image_rect'), + ('buffer/input1', 'buffer/left/camera_info_resized'), + ('input1', 'left/camera_info'), + ('buffer/input2', 'buffer/right/image_resized'), + ('input2', 'right/image_rect'), + ('buffer/input3', 'buffer/right/camera_info_resized'), + ('input3', 'right/camera_info')], + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestStereoGraph.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'sensor_msgs/msg/PointCloud2', + }], + remappings=[ + ('output', 'points2')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestStereoGraph.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_left_resize_node, + prep_right_resize_node, + playback_node, + monitor_node, + disparity_node, + pointcloud_node + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestStereoGraph.generate_test_description_with_nsys(launch_setup) + + +class TestStereoGraph(ROS2BenchmarkTest): + """Performance test for stereo image pointcloud graph.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='Stereo Image Pointcloud Graph Benchmark', + input_data_path=ROSBAG_PATH, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=100.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=100, + custom_report_info={'data_resolution': IMAGE_RESOLUTION} + ) + + def test_benchmark(self): + self.run_benchmark() diff --git a/scripts/stereo_image_proc_node.py b/scripts/stereo_image_proc_node.py new file mode 100644 index 0000000..019a1d8 --- /dev/null +++ b/scripts/stereo_image_proc_node.py @@ -0,0 +1,190 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Performance test for stereo_image_proc::DisparityNode. + +The graph consists of the following: +- Preprocessors: + 1. PrepLeftResizeNode, PrepRightResizeNode: resizes images to quarter HD +- Graph under Test: + 1. DisparityNode: creates disparity images from stereo pair + +Required: +- Packages: + - stereo_image_proc +- Datasets: + - assets/datasets/r2b_dataset/r2b_hideaway +""" + +import os + +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode + +from ros2_benchmark import ImageResolution +from ros2_benchmark import ROS2BenchmarkConfig, ROS2BenchmarkTest + +IMAGE_RESOLUTION = ImageResolution.QUARTER_HD +ROSBAG_PATH = 'datasets/r2b_dataset/r2b_hideaway' + +def launch_setup(container_prefix, container_sigterm_timeout): + """Generate launch description for benchmarking stereo_image_proc::DisparityNode.""" + + env = os.environ.copy() + env['OSPL_VERBOSITY'] = '8' # 8 = OS_NONE + # bare minimum formatting for console output matching + env['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{message}' + + disparity_node = ComposableNode( + name='DisparityNode', + namespace=TestDisparityNode.generate_namespace(), + package='stereo_image_proc', + plugin='stereo_image_proc::DisparityNode', + parameters=[{ + 'queue_size': 500, + 'approx': False, + 'use_system_default_qos': False + }], + remappings=[ + ('/left/camera_info', '/left/camera_info'), + ('/right/camera_info', '/right/camera_info'), + ('/left/image_rect', '/left/image_rect'), + ('/right/image_rect', '/right/image_rect')], + ) + + data_loader_node = ComposableNode( + name='DataLoaderNode', + namespace=TestDisparityNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::DataLoaderNode', + remappings=[('hawk_0_left_rgb_image', 'data_loader/left_image'), + ('hawk_0_left_rgb_camera_info', 'data_loader/left_camera_info'), + ('hawk_0_right_rgb_image', 'data_loader/right_image'), + ('hawk_0_right_rgb_camera_info', 'data_loader/right_camera_info')] + ) + + prep_left_resize_node = ComposableNode( + name='PrepLeftResizeNode', + namespace=TestDisparityNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/left_image'), + ('image/camera_info', 'data_loader/left_camera_info'), + ('resize/image_raw', 'buffer/left/image_resized'), + ('resize/camera_info', 'buffer/left/camera_info_resized'), + ] + ) + + prep_right_resize_node = ComposableNode( + name='PrepRightResizeNode', + namespace=TestDisparityNode.generate_namespace(), + package='image_proc', + plugin='image_proc::ResizeNode', + parameters=[{ + 'width': IMAGE_RESOLUTION['width'], + 'height': IMAGE_RESOLUTION['height'], + 'use_scale': False, + }], + remappings=[ + ('image/image_raw', 'data_loader/right_image'), + ('image/camera_info', 'data_loader/right_camera_info'), + ('resize/image_raw', 'buffer/right/image_resized'), + ('resize/camera_info', 'buffer/right/camera_info_resized'), + ] + ) + + playback_node = ComposableNode( + name='PlaybackNode', + namespace=TestDisparityNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::PlaybackNode', + parameters=[{ + 'data_formats': [ + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo', + 'sensor_msgs/msg/Image', + 'sensor_msgs/msg/CameraInfo'], + }], + remappings=[('buffer/input0', 'buffer/left/image_resized'), + ('input0', 'left/image_rect'), + ('buffer/input1', 'buffer/left/camera_info_resized'), + ('input1', 'left/camera_info'), + ('buffer/input2', 'buffer/right/image_resized'), + ('input2', 'right/image_rect'), + ('buffer/input3', 'buffer/right/camera_info_resized'), + ('input3', 'right/camera_info')], + ) + + monitor_node = ComposableNode( + name='MonitorNode', + namespace=TestDisparityNode.generate_namespace(), + package='ros2_benchmark', + plugin='ros2_benchmark::MonitorNode', + parameters=[{ + 'monitor_data_format': 'stereo_msgs/msg/DisparityImage', + }], + remappings=[ + ('output', 'disparity')], + ) + + composable_node_container = ComposableNodeContainer( + name='container', + namespace=TestDisparityNode.generate_namespace(), + package='rclcpp_components', + executable='component_container_mt', + prefix=container_prefix, + sigterm_timeout=container_sigterm_timeout, + composable_node_descriptions=[ + data_loader_node, + prep_left_resize_node, + prep_right_resize_node, + playback_node, + monitor_node, + disparity_node + ], + output='screen' + ) + + return [composable_node_container] + +def generate_test_description(): + return TestDisparityNode.generate_test_description_with_nsys(launch_setup) + + +class TestDisparityNode(ROS2BenchmarkTest): + """Performance test for stereo_image_proc::DisparityNode.""" + + # Custom configurations + config = ROS2BenchmarkConfig( + benchmark_name='stereo_image_proc::DisparityNode Benchmark', + input_data_path=ROSBAG_PATH, + # Upper and lower bounds of peak throughput search window + publisher_upper_frequency=100.0, + publisher_lower_frequency=10.0, + # The number of frames to be buffered + playback_message_buffer_size=50, + custom_report_info={'data_resolution': IMAGE_RESOLUTION} + ) + + def test_benchmark(self): + self.run_benchmark()