Skip to content

Commit 7de0fcc

Browse files
Merge pull request #7 from NVIDIA-ISAAC-ROS/release-dp3.1
Isaac ROS 0.31.0 (DP3.1)
2 parents caf9d45 + 0be990b commit 7de0fcc

File tree

7 files changed

+23
-25
lines changed

7 files changed

+23
-25
lines changed

README.md

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -35,9 +35,10 @@ This package is powered by [NVIDIA Isaac Transport for ROS (NITROS)](https://dev
3535

3636
The following table summarizes the per-platform performance statistics of sample graphs that use this package, with links included to the full benchmark output. These benchmark configurations are taken from the [Isaac ROS Benchmark](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark#list-of-isaac-ros-benchmarks) collection, based on the [`ros2_benchmark`](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark) framework.
3737

38-
| Sample Graph | Input Size | AGX Orin | Orin NX | Orin Nano 8GB | x86_64 w/ RTX 3060 Ti |
39-
| ---------------------------------------------------------------------------------------------------------------------------------------------------- | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------- |
40-
| [Occupancy Grid Localizer Node](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/scripts//isaac_ros_grid_localizer_node.py) | ~50 sq. m | [16.0 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-agx_orin.json)<br>79 ms | [7.33 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-orin_nx.json)<br>150 ms | [5.16 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-orin_nano_8gb.json)<br>220 ms | [46.5 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-x86_64_rtx_3060Ti.json)<br>33 ms |
38+
| Sample Graph | Input Size | AGX Orin | Orin NX | Orin Nano 8GB | x86_64 w/ RTX 4060 Ti |
39+
| ---------------------------------------------------------------------------------------------------------------------------------------------------- | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- |
40+
| [Occupancy Grid Localizer Node](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/scripts//isaac_ros_grid_localizer_node.py) | ~50 sq. m | [15.9 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-agx_orin.json)<br>65 ms | [7.33 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-orin_nx.json)<br>140 ms | [5.17 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-orin_nano.json)<br>200 ms | [50.1 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_grid_localizer_node-nuc_4060ti.json)<br>20 ms |
41+
4142

4243

4344
## Table of Contents
@@ -81,7 +82,7 @@ The following table summarizes the per-platform performance statistics of sample
8182

8283
## Latest Update
8384

84-
2023-04-05: Added `isaac_ros_occupancy_grid_localizer`
85+
2023-05-25: Performance improvements.
8586

8687
## Supported Platforms
8788

@@ -362,4 +363,5 @@ For solutions to problems with Isaac ROS, please check [here](https://github.com
362363
363364
| Date | Changes |
364365
| ---------- | ------------------------------------------ |
366+
| 2023-05-25 | Performance improvements |
365367
| 2023-04-05 | Added `isaac_ros_occupancy_grid_localizer` |

isaac_ros_occupancy_grid_localizer/config/occupancy_grid_localizer_node.yaml

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -221,7 +221,7 @@ components:
221221
allocator: allocator
222222
cuda_stream: cuda_stream/cuda_stream
223223
---
224-
name: vault
224+
name: sink
225225
components:
226226
- name: signal
227227
type: nvidia::gxf::DoubleBufferReceiver
@@ -232,12 +232,10 @@ components:
232232
parameters:
233233
receiver: signal
234234
min_size: 1
235-
- name: vault
236-
type: nvidia::gxf::Vault
235+
- name: sink
236+
type: nvidia::isaac_ros::MessageRelay
237237
parameters:
238238
source: signal
239-
max_waiting_count: 1
240-
drop_waiting: false
241239
---
242240
components:
243241
- name: edge0
@@ -264,16 +262,16 @@ components:
264262
type: nvidia::gxf::Connection
265263
parameters:
266264
source: localization_to_pose3d/tx_pose3d_cov
267-
target: vault/signal
265+
target: sink/signal
268266
---
269267
components:
270268
- name: clock
271269
type: nvidia::gxf::RealtimeClock
272-
- type: nvidia::gxf::MultiThreadScheduler
270+
- type: nvidia::gxf::GreedyScheduler
273271
parameters:
274272
clock: clock
275-
worker_thread_number: 8
276273
stop_on_deadlock: false
274+
check_recession_period_us: 100
277275
- type: nvidia::gxf::JobStatistics
278276
parameters:
279277
clock: clock

isaac_ros_occupancy_grid_localizer/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>isaac_ros_occupancy_grid_localizer</name>
24-
<version>0.30.0</version>
24+
<version>0.31.0</version>
2525
<description>Occupancy Grid Global Localizer.</description>
2626

2727
<maintainer email="[email protected]">Ashwin Varghese Kuruttukulam</maintainer>

isaac_ros_occupancy_grid_localizer/src/occupancy_grid_localizer_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ constexpr char INPUT_COMPONENT_KEY_FLATSCAN[] = "flatscan_beams_tensor_copier/rx
7474
constexpr char INPUT_DEFAULT_TENSOR_FORMAT_FLATSCAN[] = "nitros_flat_scan";
7575
constexpr char INPUT_TOPIC_NAME_FLATSCAN[] = "flatscan_localization";
7676

77-
constexpr char OUTPUT_COMPONENT_KEY_LOC_RESULT[] = "vault/vault";
77+
constexpr char OUTPUT_COMPONENT_KEY_LOC_RESULT[] = "sink/sink";
7878
constexpr char OUTPUT_DEFAULT_TENSOR_FORMAT_LOC_RESULT[] = "nitros_pose_cov_stamped";
7979
constexpr char OUTPUT_TOPIC_NAME_LOC_RESULT[] = "localization_result";
8080
constexpr char OUTPUT_FRAME_ID_MAP_KEY[] = "map";

isaac_ros_pointcloud_utils/config/pointcloud_to_flatscan_node.yaml

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -56,9 +56,9 @@ components:
5656
max_points: 691200
5757
---
5858
###########################
59-
# Vault for ROS Publisher #
59+
# Sink for ROS Publisher #
6060
###########################
61-
name: vault
61+
name: sink
6262
components:
6363
- name: signal
6464
type: nvidia::gxf::DoubleBufferReceiver
@@ -69,28 +69,26 @@ components:
6969
parameters:
7070
receiver: signal
7171
min_size: 1
72-
- name: vault
73-
type: nvidia::gxf::Vault
72+
- name: sink
73+
type: nvidia::isaac_ros::MessageRelay
7474
parameters:
7575
source: signal
76-
max_waiting_count: 1
77-
drop_waiting: false
7876
---
7977
components:
8078
- name: edge0
8179
type: nvidia::gxf::Connection
8280
parameters:
8381
source: pointcloud_to_flatscan/tx_flatscan
84-
target: vault/signal
82+
target: sink/signal
8583
---
8684
components:
8785
- name: clock
8886
type: nvidia::gxf::RealtimeClock
89-
- type: nvidia::gxf::MultiThreadScheduler
87+
- type: nvidia::gxf::GreedyScheduler
9088
parameters:
9189
clock: clock
92-
worker_thread_number: 8
9390
stop_on_deadlock: false
91+
check_recession_period_us: 100
9492
- type: nvidia::gxf::JobStatistics
9593
parameters:
9694
clock: clock

isaac_ros_pointcloud_utils/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>isaac_ros_pointcloud_utils</name>
24-
<version>0.30.0</version>
24+
<version>0.31.0</version>
2525
<description>Isaac ROS Point Cloud Utilities.</description>
2626

2727
<maintainer email="[email protected]">Ashwin Varghese Kuruttukulam</maintainer>

isaac_ros_pointcloud_utils/src/pointcloud_to_flatscan_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ constexpr char INPUT_COMPONENT_KEY_POINTCLOUD[] = "pointcloud_to_flatscan/rx_poi
5454
constexpr char INPUT_DEFAULT_TENSOR_FORMAT_POINTCLOUD[] = "nitros_point_cloud";
5555
constexpr char INPUT_TOPIC_NAME_POINTCLOUD[] = "pointcloud";
5656

57-
constexpr char OUTPUT_COMPONENT_KEY_FLATSCAN[] = "vault/vault";
57+
constexpr char OUTPUT_COMPONENT_KEY_FLATSCAN[] = "sink/sink";
5858
constexpr char OUTPUT_DEFAULT_TENSOR_FORMAT_FLATSCAN[] = "nitros_flat_scan";
5959
constexpr char OUTPUT_TOPIC_NAME_FLATSCAN[] = "flatscan";
6060

0 commit comments

Comments
 (0)