diff --git a/README.md b/README.md
index 14738d4..36e5d59 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
# Isaac ROS Object Detection
-Hardware-accelerated, deep learned model support for object detection including DetectNet.
+NVIDIA-accelerated, deep learned model support for object detection including DetectNet.
@@ -60,9 +60,10 @@ This package is powered by [NVIDIA Isaac Transport for ROS (NITROS)](https://dev
## Performance
-| Sample Graph
| Input Size
| AGX Orin
| Orin NX
| Orin Nano 8GB
| x86_64 w/ RTX 4060 Ti
|
-|----------------------------------------------------------------------------------------------------------------------------------------------------------------|--------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------|-----------------------------------------------------------------------------------------------------------------------------------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------|
-| [DetectNet Object Detection Graph](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/scripts/isaac_ros_detectnet_graph.py)
| 544p
| [232 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-agx_orin.json)
11 ms
| [105 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-orin_nx.json)
15 ms
| [74.2 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-orin_nano.json)
22 ms
| [644 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-nuc_4060ti.json)
5.6 ms
|
+| Sample Graph
| Input Size
| AGX Orin
| Orin NX
| Orin Nano 8GB
| x86_64 w/ RTX 4060 Ti
| x86_64 w/ RTX 4090
|
+|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|--------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------|
+| [RT-DETR Object Detection Graph](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/benchmarks/isaac_ros_rtdetr_benchmark/scripts/isaac_ros_rtdetr_graph.py)
SyntheticaDETR
| 720p
| [71.9 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_rtdetr_graph-agx_orin.json)
24 ms @ 30Hz
| [30.8 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_rtdetr_graph-orin_nx.json)
41 ms @ 30Hz
| [21.3 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_rtdetr_graph-orin_nano.json)
61 ms @ 30Hz
| [205 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_rtdetr_graph-nuc_4060ti.json)
8.7 ms @ 30Hz
| [400 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_rtdetr_graph-x86_4090.json)
6.3 ms @ 30Hz
|
+| [DetectNet Object Detection Graph](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/benchmarks/isaac_ros_detectnet_benchmark/scripts/isaac_ros_detectnet_graph.py)
| 544p
| [165 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-agx_orin.json)
20 ms @ 30Hz
| [115 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-orin_nx.json)
26 ms @ 30Hz
| [63.2 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-orin_nano.json)
36 ms @ 30Hz
| [488 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-nuc_4060ti.json)
10 ms @ 30Hz
| [589 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_detectnet_graph-x86_4090.json)
10 ms @ 30Hz
|
---
@@ -80,10 +81,17 @@ Please visit the [Isaac ROS Documentation](https://nvidia-isaac-ros.github.io/re
* [ROS 2 Graph Configuration](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_detectnet/index.html#ros-2-graph-configuration)
* [Troubleshooting](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_detectnet/index.html#troubleshooting)
* [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_detectnet/index.html#api)
+* [`isaac_ros_rtdetr`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_rtdetr/index.html)
+ * [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_rtdetr/index.html#quickstart)
+ * [Try More Examples](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_rtdetr/index.html#try-more-examples)
+ * [Troubleshooting](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_rtdetr/index.html#troubleshooting)
+ * [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_rtdetr/index.html#api)
* [`isaac_ros_yolov8`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_yolov8/index.html)
* [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_yolov8/index.html#quickstart)
+ * [Troubleshooting](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_yolov8/index.html#troubleshooting)
* [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_yolov8/index.html#api)
+ * [Usage](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_object_detection/isaac_ros_yolov8/index.html#usage)
## Latest
-Update 2023-10-18: Adding NITROS YOLOv8 decoder.
+Update 2024-05-30: Added RT-DETR object detection package
diff --git a/gxf_isaac_detectnet/CMakeLists.txt b/gxf_isaac_detectnet/CMakeLists.txt
new file mode 100644
index 0000000..bb746aa
--- /dev/null
+++ b/gxf_isaac_detectnet/CMakeLists.txt
@@ -0,0 +1,66 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2023-2024 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.22.1)
+project(gxf_isaac_detectnet LANGUAGES C CXX)
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-fPIC -w)
+endif()
+
+find_package(ament_cmake_auto REQUIRED)
+ament_auto_find_build_dependencies()
+
+# Dependencies
+find_package(Eigen3 3.3 REQUIRED NO_MODULE)
+find_package(isaac_ros_nitros_detection2_d_array_type REQUIRED)
+find_package(yaml-cpp)
+
+# DetectNet extension
+ament_auto_add_library(${PROJECT_NAME} SHARED
+ gxf/detectnet/detectnet.cpp
+ gxf/detectnet/detectnet_decoder.cpp
+ gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
+ gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
+ gxf/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
+)
+
+target_include_directories(${PROJECT_NAME} PRIVATE
+ ${CMAKE_CURRENT_SOURCE_DIR}/gxf
+ ${isaac_ros_nitros_detection2_d_array_type_INCLUDE_DIRS}
+ ${CMAKE_CURRENT_SOURCE_DIR}/gxf/deepstream_utils/include
+ ${CMAKE_CURRENT_SOURCE_DIR}/gxf/deepstream_utils/nvdsinfer/include
+ ${CMAKE_CURRENT_SOURCE_DIR}/gxf/deepstream_utils/nvdsinferutils/include
+ ${CMAKE_CURRENT_SOURCE_DIR}/gxf/deepstream_utils/nvdsinferutils/dbscan
+)
+
+target_link_libraries(${PROJECT_NAME}
+ Eigen3::Eigen
+ ${isaac_ros_nitros_detection2_d_array_type_LIBRARIES}
+ yaml-cpp
+)
+
+set_target_properties(${PROJECT_NAME} PROPERTIES
+ BUILD_WITH_INSTALL_RPATH TRUE
+ BUILD_RPATH_USE_ORIGIN TRUE
+ INSTALL_RPATH_USE_LINK_PATH TRUE
+)
+
+# Install the binary file
+install(TARGETS ${PROJECT_NAME} DESTINATION share/${PROJECT_NAME}/gxf/lib)
+
+ament_auto_package(INSTALL_TO_SHARE)
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/include/nvds_transform.h b/gxf_isaac_detectnet/gxf/deepstream_utils/include/nvds_transform.h
similarity index 98%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/include/nvds_transform.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/include/nvds_transform.h
index d3eb854..74e383d 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/include/nvds_transform.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/include/nvds_transform.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2020-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2020-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer.h
similarity index 99%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer.h
index c8cdd94..b8a7fcc 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2017-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2017-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h
similarity index 99%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h
index ff3ec3c..7400a17 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_context.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h
similarity index 99%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h
index bb1679b..201a031 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinfer/include/nvdsinfer_custom_impl.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2017-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2017-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
similarity index 99%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
index 788d9c5..beb17bf 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
similarity index 99%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
index a2c1e9b..a930132 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
similarity index 98%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
index f2c41fc..e3c0a9e 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h
similarity index 98%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h
index 154e335..48e204c 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_dbscan.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h
similarity index 96%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h
index 5d2591b..7ad34c2 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_tlt.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2019-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2019-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h
similarity index 93%
rename from isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h
rename to gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h
index 6872e2a..f45ef52 100644
--- a/isaac_ros_detectnet/gxf/detectnet/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h
+++ b/gxf_isaac_detectnet/gxf/deepstream_utils/nvdsinferutils/include/nvdsinfer_utils.h
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2018-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2018-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/detectnet.cpp b/gxf_isaac_detectnet/gxf/detectnet/detectnet.cpp
similarity index 95%
rename from isaac_ros_detectnet/gxf/detectnet/detectnet.cpp
rename to gxf_isaac_detectnet/gxf/detectnet/detectnet.cpp
index 83751be..d90fb63 100644
--- a/isaac_ros_detectnet/gxf/detectnet/detectnet.cpp
+++ b/gxf_isaac_detectnet/gxf/detectnet/detectnet.cpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2022-2024 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.
diff --git a/isaac_ros_detectnet/gxf/detectnet/detectnet_decoder.cpp b/gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.cpp
similarity index 98%
rename from isaac_ros_detectnet/gxf/detectnet/detectnet_decoder.cpp
rename to gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.cpp
index e83668d..8111832 100644
--- a/isaac_ros_detectnet/gxf/detectnet/detectnet_decoder.cpp
+++ b/gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.cpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2022-2024 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.
@@ -23,7 +23,7 @@
#include "gxf/multimedia/camera.hpp"
#include "gxf/multimedia/video.hpp"
-#include "gxf/std/parameter_parser_std.hpp"
+#include "gxf/core/parameter_parser_std.hpp"
#include "gxf/std/timestamp.hpp"
#include "cuda.h"
#include "cuda_runtime.h"
@@ -272,9 +272,9 @@ gxf_result_t DetectnetDecoder::tick() noexcept
return GXF_FAILURE;
}
- std::unique_ptr bbox_tensor_arr(new float[bbox_tensor->element_count()]);
+ float bbox_tensor_arr[bbox_tensor->size() / sizeof(float)]; // since data in tensor is kFloat32
const cudaError_t cuda_error_bbox_tensor = cudaMemcpy(
- bbox_tensor_arr.get(), bbox_tensor->pointer(),
+ &bbox_tensor_arr, bbox_tensor->pointer(),
bbox_tensor->size(), cudaMemcpyDeviceToHost);
if (cuda_error_bbox_tensor != cudaSuccess) {
GXF_LOG_ERROR("Error while copying kernel: %s", cudaGetErrorString(cuda_error_bbox_tensor));
diff --git a/isaac_ros_detectnet/gxf/detectnet/include/detectnet/detectnet_decoder.hpp b/gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.hpp
similarity index 95%
rename from isaac_ros_detectnet/gxf/detectnet/include/detectnet/detectnet_decoder.hpp
rename to gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.hpp
index 45f2c78..6bdde4d 100644
--- a/isaac_ros_detectnet/gxf/detectnet/include/detectnet/detectnet_decoder.hpp
+++ b/gxf_isaac_detectnet/gxf/detectnet/detectnet_decoder.hpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2022-2024 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.
@@ -22,7 +22,7 @@
#include "gxf/core/gxf.h"
#include "gxf/core/parameter.hpp"
#include "gxf/std/codelet.hpp"
-#include "gxf/std/parameter_parser_std.hpp"
+#include "gxf/core/parameter_parser_std.hpp"
#include "gxf/std/receiver.hpp"
#include "gxf/std/transmitter.hpp"
#include "detection2_d_array_message.hpp"
diff --git a/gxf_isaac_detectnet/package.xml b/gxf_isaac_detectnet/package.xml
new file mode 100644
index 0000000..61f365e
--- /dev/null
+++ b/gxf_isaac_detectnet/package.xml
@@ -0,0 +1,44 @@
+
+
+
+
+
+
+ gxf_isaac_detectnet
+ 3.0.0
+ Detectnet GXF extension.
+
+ Isaac ROS Maintainers
+ Apache-2.0
+ https://developer.nvidia.com/isaac-ros-gems/
+ CY Chen
+
+ ament_cmake_auto
+
+ isaac_ros_common
+ isaac_ros_gxf
+ isaac_ros_nitros_detection2_d_array_type
+
+ ament_lint_auto
+ ament_lint_common
+
+
+ ament_cmake
+
+
diff --git a/isaac_ros_detectnet/CMakeLists.txt b/isaac_ros_detectnet/CMakeLists.txt
index 9710830..3342678 100644
--- a/isaac_ros_detectnet/CMakeLists.txt
+++ b/isaac_ros_detectnet/CMakeLists.txt
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2022-2024 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.
@@ -30,14 +30,11 @@ find_package(ament_cmake_python REQUIRED)
ament_auto_add_library(detectnet_decoder_node SHARED src/detectnet_decoder_node.cpp)
rclcpp_components_register_nodes(detectnet_decoder_node "nvidia::isaac_ros::detectnet::DetectNetDecoderNode")
set(node_plugins "${node_plugins}nvidia::isaac_ros::detectnet::DetectNetDecoderNode;$\n")
-
-### Install extensions built from source
-
-# DetectNet
-add_subdirectory(gxf/detectnet)
-install(TARGETS gxf_detectnet DESTINATION share/${PROJECT_NAME}/gxf/lib/detectnet)
-
-### End extensions
+set_target_properties(detectnet_decoder_node PROPERTIES
+ BUILD_WITH_INSTALL_RPATH TRUE
+ BUILD_RPATH_USE_ORIGIN TRUE
+ INSTALL_RPATH_USE_LINK_PATH TRUE
+)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
@@ -58,11 +55,11 @@ ament_python_install_package(${PROJECT_NAME})
install(PROGRAMS
scripts/isaac_ros_detectnet_visualizer.py
- DESTINATION lib/${PROJECT_NAME}
+ scripts/setup_model.sh
+DESTINATION lib/${PROJECT_NAME}
)
install(DIRECTORY
- resources/rosbags/detectnet_rosbag
DESTINATION share/${PROJECT_NAME}
)
diff --git a/isaac_ros_detectnet/config/detectnet_node.yaml b/isaac_ros_detectnet/config/detectnet_node.yaml
index 8a47472..64417d0 100644
--- a/isaac_ros_detectnet/config/detectnet_node.yaml
+++ b/isaac_ros_detectnet/config/detectnet_node.yaml
@@ -22,12 +22,10 @@ components:
type: nvidia::gxf::DoubleBufferReceiver
parameters:
capacity: 12
- policy: 0
- name: detections_out
type: nvidia::gxf::DoubleBufferTransmitter
parameters:
capacity: 12
- policy: 0
- name: allocator
type: nvidia::gxf::UnboundedAllocator
- name: detectnet_decoder
@@ -64,7 +62,6 @@ components:
type: nvidia::gxf::DoubleBufferReceiver
parameters:
capacity: 2
- policy: 0
- type: nvidia::gxf::MessageAvailableSchedulingTerm
parameters:
receiver: signal
diff --git a/isaac_ros_detectnet/config/hawk_config.pbtxt b/isaac_ros_detectnet/config/hawk_config.pbtxt
new file mode 100644
index 0000000..7e85019
--- /dev/null
+++ b/isaac_ros_detectnet/config/hawk_config.pbtxt
@@ -0,0 +1,29 @@
+name: "peoplenet"
+platform: "tensorrt_plan"
+max_batch_size: 16
+input [
+ {
+ name: "input_1"
+ data_type: TYPE_FP32
+ format: FORMAT_NCHW
+ dims: [ 3, 1200, 1920 ]
+ }
+]
+output [
+ {
+ name: "output_bbox/BiasAdd"
+ data_type: TYPE_FP32
+ dims: [ 12, 75, 120]
+ },
+ {
+ name: "output_cov/Sigmoid"
+ data_type: TYPE_FP32
+ dims: [ 3, 75, 120]
+ }
+]
+dynamic_batching { }
+version_policy: {
+ specific {
+ versions: [ 1 ]
+ }
+}
diff --git a/isaac_ros_detectnet/resources/isaac_sim_config.pbtxt b/isaac_ros_detectnet/config/isaac_sim_config.pbtxt
similarity index 96%
rename from isaac_ros_detectnet/resources/isaac_sim_config.pbtxt
rename to isaac_ros_detectnet/config/isaac_sim_config.pbtxt
index 21cc957..118dce6 100644
--- a/isaac_ros_detectnet/resources/isaac_sim_config.pbtxt
+++ b/isaac_ros_detectnet/config/isaac_sim_config.pbtxt
@@ -1,4 +1,4 @@
-name: "detectnet"
+name: "peoplenet"
platform: "tensorrt_plan"
max_batch_size: 16
input [
diff --git a/isaac_ros_detectnet/config/params.yaml b/isaac_ros_detectnet/config/params.yaml
index 6d36dc8..da351d9 100644
--- a/isaac_ros_detectnet/config/params.yaml
+++ b/isaac_ros_detectnet/config/params.yaml
@@ -16,9 +16,7 @@
#
# SPDX-License-Identifier: Apache-2.0
---
-model_repository_paths:
- - '/tmp/models'
-model_name: 'detectnet'
+model_name: 'peoplenet'
bounding_box_scale: 35.0
bounding_box_offset: 0.0
diff --git a/isaac_ros_detectnet/config/params_isaac_sim.yaml b/isaac_ros_detectnet/config/params_isaac_sim.yaml
index 34fea37..19ba38f 100644
--- a/isaac_ros_detectnet/config/params_isaac_sim.yaml
+++ b/isaac_ros_detectnet/config/params_isaac_sim.yaml
@@ -16,8 +16,6 @@
#
# SPDX-License-Identifier: Apache-2.0
---
-model_repository_paths:
- - '/tmp/models'
model_name: 'detectnet'
bounding_box_scale: 35.0
bounding_box_offset: 0.0
diff --git a/isaac_ros_detectnet/resources/peoplenet_config.pbtxt b/isaac_ros_detectnet/config/peoplenet_config.pbtxt
similarity index 100%
rename from isaac_ros_detectnet/resources/peoplenet_config.pbtxt
rename to isaac_ros_detectnet/config/peoplenet_config.pbtxt
diff --git a/isaac_ros_detectnet/resources/quickstart_config.pbtxt b/isaac_ros_detectnet/config/quickstart_config.pbtxt
similarity index 96%
rename from isaac_ros_detectnet/resources/quickstart_config.pbtxt
rename to isaac_ros_detectnet/config/quickstart_config.pbtxt
index 4cda0d1..e7ebe05 100644
--- a/isaac_ros_detectnet/resources/quickstart_config.pbtxt
+++ b/isaac_ros_detectnet/config/quickstart_config.pbtxt
@@ -1,4 +1,4 @@
-name: "detectnet"
+name: "peoplenet"
platform: "tensorrt_plan"
max_batch_size: 16
input [
diff --git a/isaac_ros_detectnet/config/realsense_config.pbtxt b/isaac_ros_detectnet/config/realsense_config.pbtxt
new file mode 100644
index 0000000..cb837b7
--- /dev/null
+++ b/isaac_ros_detectnet/config/realsense_config.pbtxt
@@ -0,0 +1,29 @@
+name: "peoplenet"
+platform: "tensorrt_plan"
+max_batch_size: 16
+input [
+ {
+ name: "input_1"
+ data_type: TYPE_FP32
+ format: FORMAT_NCHW
+ dims: [ 3, 480, 640 ]
+ }
+]
+output [
+ {
+ name: "output_bbox/BiasAdd"
+ data_type: TYPE_FP32
+ dims: [ 12, 30, 40]
+ },
+ {
+ name: "output_cov/Sigmoid"
+ data_type: TYPE_FP32
+ dims: [ 3, 30, 40]
+ }
+]
+dynamic_batching { }
+version_policy: {
+ specific {
+ versions: [ 1 ]
+ }
+}
diff --git a/isaac_ros_detectnet/gxf/AMENT_IGNORE b/isaac_ros_detectnet/gxf/AMENT_IGNORE
deleted file mode 100644
index e69de29..0000000
diff --git a/isaac_ros_detectnet/gxf/detectnet/CMakeLists.txt b/isaac_ros_detectnet/gxf/detectnet/CMakeLists.txt
deleted file mode 100644
index 30e5df7..0000000
--- a/isaac_ros_detectnet/gxf/detectnet/CMakeLists.txt
+++ /dev/null
@@ -1,55 +0,0 @@
-# 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
-
-project(gxf_detectnet LANGUAGES C CXX)
-
-# Dependencies
-find_package(Eigen3 3.3 REQUIRED NO_MODULE)
-find_package(GXF ${ISAAC_ROS_GXF_VERSION} MODULE REQUIRED
- COMPONENTS
- std
-)
-find_package(isaac_ros_nitros_detection2_d_array_type REQUIRED)
-find_package(yaml-cpp)
-
-# DetectNet extension
-add_library(gxf_detectnet SHARED
- detectnet.cpp
- detectnet_decoder.cpp
- deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.cpp
- deepstream_utils/nvdsinferutils/dbscan/nvdsinfer_dbscan.hpp
- deepstream_utils/nvdsinferutils/dbscan/EigenDefs.hpp
-)
-set(CMAKE_INCLUDE_CURRENT_DIR TRUE)
-target_include_directories(gxf_detectnet PRIVATE
- ${isaac_ros_nitros_detection2_d_array_type_INCLUDE_DIRS}
- ${CMAKE_CURRENT_SOURCE_DIR}/include
- ${CMAKE_CURRENT_SOURCE_DIR}/include/detectnet
- ${CMAKE_CURRENT_SOURCE_DIR}/deepstream_utils/include
- ${CMAKE_CURRENT_SOURCE_DIR}/deepstream_utils/nvdsinfer/include
- ${CMAKE_CURRENT_SOURCE_DIR}/deepstream_utils/nvdsinferutils/include
- ${CMAKE_CURRENT_SOURCE_DIR}/deepstream_utils/nvdsinferutils/dbscan
-)
-target_link_libraries(gxf_detectnet
- PRIVATE
- Eigen3::Eigen
- ${isaac_ros_nitros_detection2_d_array_type_LIBRARIES}
- PUBLIC
- GXF::std
- yaml-cpp
-)
-
diff --git a/isaac_ros_detectnet/include/isaac_ros_detectnet/detectnet_decoder_node.hpp b/isaac_ros_detectnet/include/isaac_ros_detectnet/detectnet_decoder_node.hpp
index 2396c2e..eb65541 100644
--- a/isaac_ros_detectnet/include/isaac_ros_detectnet/detectnet_decoder_node.hpp
+++ b/isaac_ros_detectnet/include/isaac_ros_detectnet/detectnet_decoder_node.hpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2021-2024 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.
diff --git a/isaac_ros_detectnet/isaac_ros_detectnet/__init__.py b/isaac_ros_detectnet/isaac_ros_detectnet/__init__.py
index 6bbcb13..41b7387 100644
--- a/isaac_ros_detectnet/isaac_ros_detectnet/__init__.py
+++ b/isaac_ros_detectnet/isaac_ros_detectnet/__init__.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
diff --git a/isaac_ros_detectnet/launch/isaac_ros_detectnet.launch.py b/isaac_ros_detectnet/launch/isaac_ros_detectnet.launch.py
index b55f6f4..dcadfc5 100644
--- a/isaac_ros_detectnet/launch/isaac_ros_detectnet.launch.py
+++ b/isaac_ros_detectnet/launch/isaac_ros_detectnet.launch.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2021-2024 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.
@@ -17,36 +17,48 @@
import os
+from ament_index_python.packages import get_package_share_directory
import launch
+from launch.actions import IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
"""Generate launch description for testing relevant nodes."""
- launch_dir_path = os.path.dirname(os.path.realpath(__file__))
- config = launch_dir_path + '/../config/params.yaml'
- model_dir_path = '/tmp/models'
-
+ isaac_ros_ws_path = os.environ.get('ISAAC_ROS_WS', '')
+ model_dir_path = os.path.join(isaac_ros_ws_path,
+ 'isaac_ros_assets/isaac_ros_detectnet/models')
# Read labels from text file
labels_file_path = f'{model_dir_path}/detectnet/1/labels.txt'
+ with open(labels_file_path, 'r') as fd:
+ label_list = fd.read().strip().splitlines()
+ launch_dir_path = os.path.dirname(os.path.realpath(__file__))
+ config = launch_dir_path + '/../config/params.yaml'
with open(labels_file_path, 'r') as fd:
label_list = fd.read().strip().splitlines()
- encoder_node = ComposableNode(
- name='dnn_image_encoder',
- package='isaac_ros_dnn_image_encoder',
- plugin='nvidia::isaac_ros::dnn_inference::DnnImageEncoderNode',
- parameters=[{
- 'input_image_width': 1200,
- 'input_image_height': 632,
- 'network_image_width': 1200,
- 'network_image_height': 632,
- 'image_mean': [0.0, 0.0, 0.0],
- 'image_stddev': [1.0, 1.0, 1.0],
- 'enable_padding': False
- }],
- remappings=[('encoded_tensor', 'tensor_pub')]
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ detectnet_encoder_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': str(1200),
+ 'input_image_height': str(632),
+ 'network_image_width': str(1200),
+ 'network_image_height': str(632),
+ 'image_mean': str([0.0, 0.0, 0.0]),
+ 'image_stddev': str([1.0, 1.0, 1.0]),
+ 'enable_padding': 'False',
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': 'detectnet_container/detectnet_container',
+ 'dnn_image_encoder_namespace': 'detectnet_encoder',
+ 'image_input_topic': '/image',
+ 'camera_info_input_topic': '/camera_info',
+ 'tensor_output_topic': '/tensor_pub',
+ }.items(),
)
triton_node = ComposableNode(
@@ -81,8 +93,8 @@ def generate_launch_description():
package='rclcpp_components',
executable='component_container_mt',
composable_node_descriptions=[
- encoder_node, triton_node, detectnet_decoder_node],
+ triton_node, detectnet_decoder_node],
output='screen'
)
- return launch.LaunchDescription([container])
+ return launch.LaunchDescription([container, detectnet_encoder_launch])
diff --git a/isaac_ros_detectnet/launch/isaac_ros_detectnet_core.launch.py b/isaac_ros_detectnet/launch/isaac_ros_detectnet_core.launch.py
new file mode 100644
index 0000000..c8efbeb
--- /dev/null
+++ b/isaac_ros_detectnet/launch/isaac_ros_detectnet_core.launch.py
@@ -0,0 +1,97 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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
+from typing import Any, Dict
+
+from ament_index_python.packages import get_package_share_directory
+from isaac_ros_examples import IsaacROSLaunchFragment
+import launch
+
+from launch.actions import IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch_ros.descriptions import ComposableNode
+
+
+class IsaacROSDetectnetLaunchFragment(IsaacROSLaunchFragment):
+
+ @staticmethod
+ def get_composable_nodes(interface_specs: Dict[str, Any]) -> Dict[str, ComposableNode]:
+ """Generate launch description for testing relevant nodes."""
+ isaac_ros_ws_path = os.environ.get('ISAAC_ROS_WS', '')
+ model_dir_path = os.path.join(isaac_ros_ws_path,
+ 'isaac_ros_assets/models')
+ # Read labels from text file
+ labels_file_path = f'{model_dir_path}/peoplenet/1/labels.txt'
+ with open(labels_file_path, 'r') as fd:
+ label_list = fd.read().strip().splitlines()
+ launch_dir_path = os.path.dirname(os.path.realpath(__file__))
+ config = launch_dir_path + '/../config/params.yaml'
+ return {
+ 'detectnet_node': ComposableNode(
+ package='isaac_ros_detectnet',
+ plugin='nvidia::isaac_ros::detectnet::DetectNetDecoderNode',
+ name='detectnet',
+ namespace='',
+ parameters=[config,
+ {
+ 'label_list': label_list
+ }]
+ ),
+ 'triton_node': ComposableNode(
+ package='isaac_ros_triton',
+ plugin='nvidia::isaac_ros::dnn_inference::TritonNode',
+ name='triton_node',
+ namespace='',
+ parameters=[{
+ 'model_name': 'peoplenet',
+ 'model_repository_paths': [model_dir_path],
+ 'input_tensor_names': ['input_tensor'],
+ 'input_binding_names': ['input_1'],
+ 'input_tensor_formats': ['nitros_tensor_list_nchw_rgb_f32'],
+ 'output_tensor_names': ['output_cov', 'output_bbox'],
+ 'output_binding_names': ['output_cov/Sigmoid', 'output_bbox/BiasAdd'],
+ 'output_tensor_formats': ['nitros_tensor_list_nhwc_rgb_f32'],
+ 'log_level': 0
+ }]),
+ }
+
+ def get_launch_actions(interface_specs: Dict[str, Any]) -> \
+ Dict[str, launch.actions.OpaqueFunction]:
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ return {
+ 'detectnet_encoder_launch': IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': str(interface_specs['camera_resolution']['width']),
+ 'input_image_height': str(interface_specs['camera_resolution']['height']),
+ 'network_image_width': str(interface_specs['camera_resolution']['width']),
+ 'network_image_height': str(interface_specs['camera_resolution']['height']),
+ 'image_mean': str([0.0, 0.0, 0.0]),
+ 'image_stddev': str([1.0, 1.0, 1.0]),
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': '/isaac_ros_examples/container',
+ 'dnn_image_encoder_namespace': 'detectnet_encoder',
+ 'image_input_topic': '/image_rect',
+ 'camera_info_input_topic': '/camera_info_rect',
+ 'tensor_output_topic': '/tensor_pub',
+ 'keep_aspect_ratio': 'False'
+ }.items(),
+ )
+ }
diff --git a/isaac_ros_detectnet/launch/isaac_ros_detectnet_isaac_sim.launch.py b/isaac_ros_detectnet/launch/isaac_ros_detectnet_isaac_sim.launch.py
index 510f1f3..a2b7225 100644
--- a/isaac_ros_detectnet/launch/isaac_ros_detectnet_isaac_sim.launch.py
+++ b/isaac_ros_detectnet/launch/isaac_ros_detectnet_isaac_sim.launch.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2021-2024 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.
@@ -17,7 +17,10 @@
import os
+from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
+from launch.actions import IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode
@@ -26,10 +29,12 @@ def generate_launch_description():
"""Generate launch description for testing relevant nodes."""
launch_dir_path = os.path.dirname(os.path.realpath(__file__))
config = launch_dir_path + '/../config/params_isaac_sim.yaml'
- model_dir_path = '/tmp/models'
+ isaac_ros_ws_path = os.environ.get('ISAAC_ROS_WS', '')
+ model_dir_path = os.path.join(isaac_ros_ws_path,
+ 'isaac_ros_assets/models')
# Read labels from text file
- labels_file_path = f'{model_dir_path}/detectnet/1/labels.txt'
+ labels_file_path = f'{model_dir_path}/peoplenet/1/labels.txt'
with open(labels_file_path, 'r') as fd:
label_list = fd.read().strip().splitlines()
@@ -49,21 +54,27 @@ def generate_launch_description():
('resize/image', 'front_stereo_camera/left_rgb/image_resize')]
)
- encoder_node = ComposableNode(
- name='dnn_image_encoder',
- package='isaac_ros_dnn_image_encoder',
- plugin='nvidia::isaac_ros::dnn_inference::DnnImageEncoderNode',
- parameters=[{
- 'input_image_width': 1280,
- 'input_image_height': 720,
- 'network_image_width': 1280,
- 'network_image_height': 720,
- 'image_mean': [0.0, 0.0, 0.0],
- 'image_stddev': [1.0, 1.0, 1.0],
- 'enable_padding': False
- }],
- remappings=[('encoded_tensor', 'tensor_pub'),
- ('image', 'front_stereo_camera/left_rgb/image_resize')]
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ detectnet_encoder_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch',
+ 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': str(1280),
+ 'input_image_height': str(720),
+ 'network_image_width': str(1280),
+ 'network_image_height': str(720),
+ 'image_mean': str([0.0, 0.0, 0.0]),
+ 'image_stddev': str([1.0, 1.0, 1.0]),
+ 'enable_padding': 'False',
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': 'detectnet_container/detectnet_container',
+ 'dnn_image_encoder_namespace': 'detectnet_encoder',
+ 'image_input_topic': '/front_stereo_camera/left_rgb/image_resize',
+ 'camera_info_input_topic': '/front_stereo_camera/left_rgb/camerainfo_resize',
+ 'tensor_output_topic': '/tensor_pub',
+ }.items(),
)
triton_node = ComposableNode(
@@ -71,7 +82,7 @@ def generate_launch_description():
package='isaac_ros_triton',
plugin='nvidia::isaac_ros::dnn_inference::TritonNode',
parameters=[{
- 'model_name': 'detectnet',
+ 'model_name': 'peoplenet',
'model_repository_paths': [model_dir_path],
'input_tensor_names': ['input_tensor'],
'input_binding_names': ['input_1'],
@@ -98,7 +109,7 @@ def generate_launch_description():
package='rclcpp_components',
executable='component_container_mt',
composable_node_descriptions=[
- image_resize_node_left, encoder_node, triton_node, detectnet_decoder_node],
+ image_resize_node_left, triton_node, detectnet_decoder_node],
output='screen'
)
@@ -120,5 +131,7 @@ def generate_launch_description():
]
)
- return LaunchDescription([detectnet_container, detectnet_visualizer_node, rqt_image_view_node
- ])
+ return LaunchDescription([
+ detectnet_container, detectnet_encoder_launch,
+ detectnet_visualizer_node, rqt_image_view_node
+ ])
diff --git a/isaac_ros_detectnet/launch/isaac_ros_detectnet_quickstart.launch.py b/isaac_ros_detectnet/launch/isaac_ros_detectnet_quickstart.launch.py
deleted file mode 100644
index 288cdbd..0000000
--- a/isaac_ros_detectnet/launch/isaac_ros_detectnet_quickstart.launch.py
+++ /dev/null
@@ -1,50 +0,0 @@
-# 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
-
-import os
-
-from ament_index_python.packages import get_package_share_directory
-from launch import actions, LaunchDescription
-from launch.actions import IncludeLaunchDescription
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch_ros.actions import Node
-
-
-def generate_launch_description():
- my_package_dir = get_package_share_directory('isaac_ros_detectnet')
- return LaunchDescription([
- actions.ExecuteProcess(
- cmd=['ros2', 'bag', 'play', '-l',
- os.path.join(my_package_dir, 'detectnet_rosbag')]
- ),
- IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- my_package_dir, 'launch'),
- '/isaac_ros_detectnet.launch.py'])
- ),
- Node(
- package='isaac_ros_detectnet',
- executable='isaac_ros_detectnet_visualizer.py',
- name='detectnet_visualizer'
- ),
- Node(
- package='rqt_image_view',
- executable='rqt_image_view',
- name='image_view',
- arguments=['/detectnet_processed_image']
- )
- ])
diff --git a/isaac_ros_detectnet/package.xml b/isaac_ros_detectnet/package.xml
index 28384ca..a7b1af4 100644
--- a/isaac_ros_detectnet/package.xml
+++ b/isaac_ros_detectnet/package.xml
@@ -21,10 +21,10 @@ SPDX-License-Identifier: Apache-2.0
isaac_ros_detectnet
- 2.1.0
+ 3.0.0
DetectNet model processing
- Ashwin Varghese Kuruttukulam
+ Isaac ROS Maintainers
Apache-2.0
https://developer.nvidia.com/isaac-ros/
Ashwin Varghese Kuruttukulam
@@ -41,6 +41,9 @@ SPDX-License-Identifier: Apache-2.0
isaac_ros_common
+ gxf_isaac_detectnet
+ isaac_ros_image_proc
+
ament_lint_auto
ament_lint_common
isaac_ros_test
diff --git a/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/detectnet_rosbag_0.db3 b/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/detectnet_rosbag_0.db3
deleted file mode 100644
index 633937b..0000000
--- a/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/detectnet_rosbag_0.db3
+++ /dev/null
@@ -1,3 +0,0 @@
-version https://git-lfs.github.com/spec/v1
-oid sha256:ac28d83e0675471d4478604a5a02caf17fc3464b5b124e87a03fbc476b242497
-size 125300736
diff --git a/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/metadata.yaml b/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/metadata.yaml
deleted file mode 100644
index 8efc5b7..0000000
--- a/isaac_ros_detectnet/resources/rosbags/detectnet_rosbag/metadata.yaml
+++ /dev/null
@@ -1,3 +0,0 @@
-version https://git-lfs.github.com/spec/v1
-oid sha256:493e8f288cc6f517e64ab0f9c749a4d01410120566e13ff7a81aa46b11866266
-size 986
diff --git a/isaac_ros_detectnet/scripts/isaac_ros_detectnet_visualizer.py b/isaac_ros_detectnet/scripts/isaac_ros_detectnet_visualizer.py
index 875e202..f4bf011 100755
--- a/isaac_ros_detectnet/scripts/isaac_ros_detectnet_visualizer.py
+++ b/isaac_ros_detectnet/scripts/isaac_ros_detectnet_visualizer.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2021-2024 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.
diff --git a/isaac_ros_detectnet/scripts/setup_model.sh b/isaac_ros_detectnet/scripts/setup_model.sh
index 7c33825..f291cdb 100755
--- a/isaac_ros_detectnet/scripts/setup_model.sh
+++ b/isaac_ros_detectnet/scripts/setup_model.sh
@@ -1,3 +1,5 @@
+#!/bin/bash
+
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2022 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
@@ -23,7 +25,7 @@ MODEL_LINK="https://api.ngc.nvidia.com/v2/models/nvidia/tao/peoplenet/versions/d
MODEL_FILE_NAME="resnet34_peoplenet_int8.etlt"
HEIGHT="632"
WIDTH="1200"
-CONFIG_FILE_PATH="isaac_ros_detectnet/resources/peoplenet_config.pbtxt"
+CONFIG_FILE="peoplenet_config.pbtxt"
PRECISION="int8"
OUTPUT_LAYERS="output_cov/Sigmoid,output_bbox/BiasAdd"
@@ -34,7 +36,7 @@ function print_parameters() {
echo MODEL_LINK : $MODEL_LINK
echo HEIGHT : $HEIGHT
echo WIDTH : $WIDTH
- echo CONFIG_FILE_PATH : $CONFIG_FILE_PATH
+ echo CONFIG_FILE : $CONFIG_FILE
echo "***************************"
echo
}
@@ -56,12 +58,25 @@ function check_labels_files() {
fi
}
+# Function that extracts the last word in the three-word chain after "models/"
+extract_model_name() {
+ url="$1"
+ # Extract the three-word chain after "models/"
+ three_word_chain=$(echo $url | grep -oP 'models/\K([^/]+)(/[^/]+){2}')
+ # Extract the last word
+ last_word=$(echo $three_word_chain | grep -oP '[^/]+$')
+ echo $last_word
+}
+
function setup_model() {
# Download pre-trained ETLT model to appropriate directory
- echo Creating Directory : /tmp/models/detectnet/1
- rm -rf /tmp/models
- mkdir -p /tmp/models/detectnet/1
- cd /tmp/models/detectnet/1
+ # Extract model names from URLs
+ model_name_from_model_link=$(extract_model_name "$MODEL_LINK")
+ echo "Model name from model link: $model_name_from_model_link"
+ echo Creating Directory : ${ISAAC_ROS_WS}/isaac_ros_assets/models/$model_name_from_model_link/1
+ rm -rf ${ISAAC_ROS_WS}/isaac_ros_assets/models
+ mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets/models/$model_name_from_model_link/1
+ cd ${ISAAC_ROS_WS}/isaac_ros_assets/models/$model_name_from_model_link/1
echo Downloading .etlt file from $MODEL_LINK
echo From $MODEL_LINK
wget --content-disposition $MODEL_LINK -O model.zip
@@ -83,10 +98,11 @@ function setup_model() {
-e model.plan \
-o $OUTPUT_LAYERS\
$MODEL_FILE_NAME
- echo Copying .pbtxt config file to /tmp/models/detectnet
+ echo Copying .pbtxt config file to ${ISAAC_ROS_WS}/isaac_ros_assets/models/$model_name_from_model_link
cd /workspaces/isaac_ros-dev/src/isaac_ros_object_detection/isaac_ros_detectnet
- cp $CONFIG_FILE_PATH \
- /tmp/models/detectnet/config.pbtxt
+ export ISAAC_ROS_DETECTNET_PATH=$(ros2 pkg prefix isaac_ros_detectnet --share)
+ cp $ISAAC_ROS_DETECTNET_PATH/config/$CONFIG_FILE \
+ ${ISAAC_ROS_WS}/isaac_ros_assets/models/$model_name_from_model_link/config.pbtxt
echo Completed quickstart setup
}
@@ -128,7 +144,7 @@ while true; do
shift 2
;;
-c|--config-file)
- CONFIG_FILE_PATH="$2"
+ CONFIG_FILE="$2"
shift 2
;;
-p|--precision)
diff --git a/isaac_ros_detectnet/src/detectnet_decoder_node.cpp b/isaac_ros_detectnet/src/detectnet_decoder_node.cpp
index 68aed2b..604fd69 100644
--- a/isaac_ros_detectnet/src/detectnet_decoder_node.cpp
+++ b/isaac_ros_detectnet/src/detectnet_decoder_node.cpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2021-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2021-2024 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.
@@ -62,7 +62,7 @@ const std::vector> EXTENSIONS = {
{"isaac_ros_gxf", "gxf/lib/multimedia/libgxf_multimedia.so"},
{"isaac_ros_gxf", "gxf/lib/serialization/libgxf_serialization.so"},
{"isaac_ros_gxf", "gxf/lib/cuda/libgxf_cuda.so"},
- {"isaac_ros_detectnet", "gxf/lib/detectnet/libgxf_detectnet.so"},
+ {"gxf_isaac_detectnet", "gxf/lib/libgxf_isaac_detectnet.so"},
};
const std::vector PRESET_EXTENSION_SPEC_NAMES = {
"isaac_ros_detectnet",
diff --git a/isaac_ros_detectnet/test/isaac_ros_detectnet_pol_test.py b/isaac_ros_detectnet/test/isaac_ros_detectnet_pol_test.py
index 05c7f81..47d85aa 100644
--- a/isaac_ros_detectnet/test/isaac_ros_detectnet_pol_test.py
+++ b/isaac_ros_detectnet/test/isaac_ros_detectnet_pol_test.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2022-2024 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.
@@ -33,14 +33,17 @@
import subprocess
import time
+from ament_index_python.packages import get_package_share_directory
from isaac_ros_test import IsaacROSBaseTest, JSONConversion
+from launch.actions import IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions.composable_node_container import ComposableNodeContainer
from launch_ros.descriptions.composable_node import ComposableNode
import pytest
import rclpy
-from sensor_msgs.msg import Image
+from sensor_msgs.msg import CameraInfo, Image
from vision_msgs.msg import Detection2DArray
_TEST_CASE_NAMESPACE = 'detectnet_node_test'
@@ -89,19 +92,22 @@ def generate_test_description():
print(
f'Finished generating engine file (took {int(time.time() - start_time)}s)')
- encoder_node = ComposableNode(
- name='DnnImageEncoderNode',
- package='isaac_ros_dnn_image_encoder',
- plugin='nvidia::isaac_ros::dnn_inference::DnnImageEncoderNode',
- namespace=IsaacROSDetectNetPipelineTest.generate_namespace(
- _TEST_CASE_NAMESPACE),
- parameters=[{
- 'input_image_width': 640,
- 'input_image_height': 368,
- 'network_image_width': 640,
- 'network_image_height': 368
- }],
- remappings=[('encoded_tensor', 'tensor_pub')]
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ centerpose_encoder_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': '640',
+ 'input_image_height': '368',
+ 'network_image_width': '640',
+ 'network_image_height': '368',
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': 'detectnet_container',
+ 'dnn_image_encoder_namespace': IsaacROSDetectNetPipelineTest.generate_namespace(
+ _TEST_CASE_NAMESPACE),
+ 'tensor_output_topic': 'tensor_pub',
+ }.items(),
)
triton_node = ComposableNode(
@@ -152,13 +158,13 @@ def generate_test_description():
executable='component_container_mt',
composable_node_descriptions=[
triton_node,
- encoder_node,
detectnet_decoder_node
],
output='screen'
)
- return IsaacROSDetectNetPipelineTest.generate_test_description([container])
+ return IsaacROSDetectNetPipelineTest.generate_test_description(
+ [container, centerpose_encoder_launch])
class IsaacROSDetectNetPipelineTest(IsaacROSBaseTest):
@@ -177,9 +183,11 @@ def test_image_detection(self, test_folder):
"""Expect the node to segment an image."""
self.generate_namespace_lookup(
- ['image', 'detectnet/detections'], _TEST_CASE_NAMESPACE)
+ ['image', 'detectnet/detections', 'camera_info'], _TEST_CASE_NAMESPACE)
image_pub = self.node.create_publisher(
Image, self.namespaces['image'], self.DEFAULT_QOS)
+ camera_info_pub = self.node.create_publisher(
+ CameraInfo, self.namespaces['camera_info'], self.DEFAULT_QOS)
received_messages = {}
detectnet_detections = self.create_logging_subscribers(
[('detectnet/detections', Detection2DArray)],
@@ -192,6 +200,9 @@ def test_image_detection(self, test_folder):
image = JSONConversion.load_image_from_json(
test_folder / 'detections.json')
image.header.stamp = self.node.get_clock().now().to_msg()
+ camera_info = CameraInfo()
+ camera_info.header = image.header
+ camera_info.distortion_model = 'plumb_bob'
ground_truth = open(test_folder.joinpath(
'expected_detections.txt'), 'r')
expected_detections = []
@@ -210,6 +221,7 @@ def test_image_detection(self, test_folder):
done = False
while time.time() < end_time:
image_pub.publish(image)
+ camera_info_pub.publish(camera_info)
rclpy.spin_once(self.node, timeout_sec=0.1)
if 'detectnet/detections' in received_messages:
diff --git a/isaac_ros_rtdetr/CMakeLists.txt b/isaac_ros_rtdetr/CMakeLists.txt
new file mode 100644
index 0000000..ab91928
--- /dev/null
+++ b/isaac_ros_rtdetr/CMakeLists.txt
@@ -0,0 +1,59 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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.22.1)
+project(isaac_ros_rtdetr LANGUAGES C CXX)
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+find_package(ament_cmake_auto REQUIRED)
+ament_auto_find_build_dependencies()
+
+# RtDetrPreprocessorNode
+ament_auto_add_library(rtdetr_preprocessor_node SHARED src/rtdetr_preprocessor_node.cpp)
+rclcpp_components_register_nodes(rtdetr_preprocessor_node "nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode")
+set(node_plugins "${node_plugins}nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode;$\n")
+
+# RtDetrDecoderNode
+ament_auto_add_library(rtdetr_decoder_node SHARED src/rtdetr_decoder_node.cpp)
+rclcpp_components_register_nodes(rtdetr_decoder_node "nvidia::isaac_ros::rtdetr::RtDetrDecoderNode")
+set(node_plugins "${node_plugins}nvidia::isaac_ros::rtdetr::RtDetrDecoderNode;$\n")
+
+if(BUILD_TESTING)
+ find_package(ament_lint_auto REQUIRED)
+ ament_lint_auto_find_test_dependencies()
+
+ # The FindPythonInterp and FindPythonLibs modules are removed
+ if(POLICY CMP0148)
+ cmake_policy(SET CMP0148 OLD)
+ endif()
+
+ find_package(launch_testing_ament_cmake REQUIRED)
+ add_launch_test(test/isaac_ros_rtdetr_pol_test.py TIMEOUT "600")
+endif()
+
+# Visualizer python scripts
+ament_python_install_package(${PROJECT_NAME})
+
+install(PROGRAMS
+ scripts/isaac_ros_rtdetr_visualizer.py
+ DESTINATION lib/${PROJECT_NAME}
+)
+
+ament_auto_package(INSTALL_TO_SHARE launch)
diff --git a/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_decoder_node.hpp b/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_decoder_node.hpp
new file mode 100644
index 0000000..8c42bc1
--- /dev/null
+++ b/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_decoder_node.hpp
@@ -0,0 +1,65 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2024 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 ISAAC_ROS_RTDETR__RTDETR_DECODER_NODE_HPP_
+#define ISAAC_ROS_RTDETR__RTDETR_DECODER_NODE_HPP_
+
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+
+#include "isaac_ros_managed_nitros/managed_nitros_subscriber.hpp"
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp"
+#include "vision_msgs/msg/detection2_d_array.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+namespace rtdetr
+{
+
+class RtDetrDecoderNode : public rclcpp::Node
+{
+public:
+ explicit RtDetrDecoderNode(const rclcpp::NodeOptions options = rclcpp::NodeOptions());
+
+ ~RtDetrDecoderNode();
+
+private:
+ void InputCallback(const nvidia::isaac_ros::nitros::NitrosTensorListView & msg);
+
+ // Subscription to input NitrosTensorList messages
+ std::shared_ptr> nitros_sub_;
+
+ // Publisher for output Detection2DArray messages
+ rclcpp::Publisher::SharedPtr pub_;
+
+ std::string labels_tensor_name_{};
+ std::string boxes_tensor_name_{};
+ std::string scores_tensor_name_{};
+ double confidence_threshold_{};
+ cudaStream_t stream_;
+};
+
+} // namespace rtdetr
+} // namespace isaac_ros
+} // namespace nvidia
+
+#endif // ISAAC_ROS_RTDETR__RTDETR_DECODER_NODE_HPP_
diff --git a/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_preprocessor_node.hpp b/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_preprocessor_node.hpp
new file mode 100644
index 0000000..93b9845
--- /dev/null
+++ b/isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_preprocessor_node.hpp
@@ -0,0 +1,68 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2024 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 ISAAC_ROS_RTDETR__RTDETR_PREPROCESSOR_NODE_HPP_
+#define ISAAC_ROS_RTDETR__RTDETR_PREPROCESSOR_NODE_HPP_
+
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+
+#include "isaac_ros_managed_nitros/managed_nitros_publisher.hpp"
+#include "isaac_ros_managed_nitros/managed_nitros_subscriber.hpp"
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp"
+#include "isaac_ros_tensor_list_interfaces/msg/tensor_list.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+namespace rtdetr
+{
+
+class RtDetrPreprocessorNode : public rclcpp::Node
+{
+public:
+ explicit RtDetrPreprocessorNode(const rclcpp::NodeOptions options = rclcpp::NodeOptions());
+
+ ~RtDetrPreprocessorNode();
+
+private:
+ void InputCallback(const nvidia::isaac_ros::nitros::NitrosTensorListView & msg);
+
+ // Subscription to input NitrosTensorList messages
+ std::shared_ptr> nitros_sub_;
+
+ // Publisher for output NitrosTensorList messages
+ std::shared_ptr> nitros_pub_;
+
+ std::string input_image_tensor_name_{};
+ std::string output_image_tensor_name_{};
+ std::string output_size_tensor_name_{};
+ int64_t image_height_{};
+ int64_t image_width_{};
+ cudaStream_t stream_;
+};
+
+} // namespace rtdetr
+} // namespace isaac_ros
+} // namespace nvidia
+
+#endif // ISAAC_ROS_RTDETR__RTDETR_PREPROCESSOR_NODE_HPP_
diff --git a/isaac_ros_rtdetr/isaac_ros_rtdetr/__init__.py b/isaac_ros_rtdetr/isaac_ros_rtdetr/__init__.py
new file mode 100644
index 0000000..34d9bfe
--- /dev/null
+++ b/isaac_ros_rtdetr/isaac_ros_rtdetr/__init__.py
@@ -0,0 +1,16 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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/isaac_ros_rtdetr/launch/isaac_ros_rtdetr.launch.py b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr.launch.py
new file mode 100644
index 0000000..9d0e772
--- /dev/null
+++ b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr.launch.py
@@ -0,0 +1,215 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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 launch
+from launch.actions import DeclareLaunchArgument
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import ComposableNodeContainer
+from launch_ros.descriptions import ComposableNode
+
+MODEL_INPUT_SIZE = 640 # RT-DETR models expect 640x640 encoded image size
+MODEL_NUM_CHANNELS = 3 # RT-DETR models expect 3 image channels
+
+
+def generate_launch_description():
+ """Generate launch description for testing relevant nodes."""
+ launch_args = [
+ DeclareLaunchArgument(
+ 'model_file_path',
+ default_value='',
+ description='The absolute file path to the ONNX file'),
+ DeclareLaunchArgument(
+ 'engine_file_path',
+ default_value='',
+ description='The absolute file path to the TensorRT engine file'),
+ DeclareLaunchArgument(
+ 'input_image_width',
+ default_value='640',
+ description='The input image width'),
+ DeclareLaunchArgument(
+ 'input_image_height',
+ default_value='480',
+ description='The input image height'),
+ DeclareLaunchArgument(
+ 'input_tensor_names',
+ default_value='["images", "orig_target_sizes"]',
+ description='A list of tensor names to bound to the specified input binding names'),
+ DeclareLaunchArgument(
+ 'input_binding_names',
+ default_value='["images", "orig_target_sizes"]',
+ description='A list of input tensor binding names (specified by model)'),
+ DeclareLaunchArgument(
+ 'output_tensor_names',
+ default_value='["labels", "boxes", "scores"]',
+ description='A list of tensor names to bound to the specified output binding names'),
+ DeclareLaunchArgument(
+ 'output_binding_names',
+ default_value='["labels", "boxes", "scores"]',
+ description='A list of output tensor binding names (specified by model)'),
+ DeclareLaunchArgument(
+ 'verbose',
+ default_value='False',
+ description='Whether TensorRT should verbosely log or not'),
+ DeclareLaunchArgument(
+ 'force_engine_update',
+ default_value='False',
+ description='Whether TensorRT should update the TensorRT engine file or not'),
+ ]
+
+ # Image Encoding parameters
+ input_image_width = LaunchConfiguration('input_image_width')
+ input_image_height = LaunchConfiguration('input_image_height')
+
+ # TensorRT parameters
+ model_file_path = LaunchConfiguration('model_file_path')
+ engine_file_path = LaunchConfiguration('engine_file_path')
+ input_tensor_names = LaunchConfiguration('input_tensor_names')
+ input_binding_names = LaunchConfiguration('input_binding_names')
+ output_tensor_names = LaunchConfiguration('output_tensor_names')
+ output_binding_names = LaunchConfiguration('output_binding_names')
+ verbose = LaunchConfiguration('verbose')
+ force_engine_update = LaunchConfiguration('force_engine_update')
+
+ resize_node = ComposableNode(
+ name='resize_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ResizeNode',
+ parameters=[{
+ 'input_width': input_image_width,
+ 'input_height': input_image_height,
+ 'output_width': MODEL_INPUT_SIZE,
+ 'output_height': MODEL_INPUT_SIZE,
+ 'keep_aspect_ratio': True,
+ 'encoding_desired': 'rgb8',
+ 'disable_padding': True
+ }]
+ )
+
+ pad_node = ComposableNode(
+ name='pad_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::PadNode',
+ parameters=[{
+ 'output_image_width': MODEL_INPUT_SIZE,
+ 'output_image_height': MODEL_INPUT_SIZE,
+ 'padding_type': 'BOTTOM_RIGHT'
+ }],
+ remappings=[(
+ 'image', 'resize/image'
+ )]
+ )
+
+ image_format_node = ComposableNode(
+ name='image_format_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ImageFormatConverterNode',
+ parameters=[{
+ 'encoding_desired': 'rgb8',
+ 'image_width': MODEL_INPUT_SIZE,
+ 'image_height': MODEL_INPUT_SIZE
+ }],
+ remappings=[
+ ('image_raw', 'padded_image'),
+ ('image', 'image_rgb')]
+ )
+
+ image_to_tensor_node = ComposableNode(
+ name='image_to_tensor_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ImageToTensorNode',
+ parameters=[{
+ 'scale': False,
+ 'tensor_name': 'image',
+ }],
+ remappings=[
+ ('image', 'image_rgb'),
+ ('tensor', 'normalized_tensor'),
+ ]
+ )
+
+ interleave_to_planar_node = ComposableNode(
+ name='interleaved_to_planar_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::InterleavedToPlanarNode',
+ parameters=[{
+ 'input_tensor_shape': [MODEL_INPUT_SIZE, MODEL_INPUT_SIZE, MODEL_NUM_CHANNELS]
+ }],
+ remappings=[
+ ('interleaved_tensor', 'normalized_tensor')
+ ]
+ )
+
+ reshape_node = ComposableNode(
+ name='reshape_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ReshapeNode',
+ parameters=[{
+ 'output_tensor_name': 'input_tensor',
+ 'input_tensor_shape': [MODEL_NUM_CHANNELS, MODEL_INPUT_SIZE, MODEL_INPUT_SIZE],
+ 'output_tensor_shape': [1, MODEL_NUM_CHANNELS, MODEL_INPUT_SIZE, MODEL_INPUT_SIZE]
+ }],
+ remappings=[
+ ('tensor', 'planar_tensor')
+ ],
+ )
+
+ rtdetr_preprocessor_node = ComposableNode(
+ name='rtdetr_preprocessor',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode',
+ remappings=[
+ ('encoded_tensor', 'reshaped_tensor')
+ ]
+ )
+
+ tensor_rt_node = ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ parameters=[{
+ 'model_file_path': model_file_path,
+ 'engine_file_path': engine_file_path,
+ 'output_binding_names': output_binding_names,
+ 'output_tensor_names': output_tensor_names,
+ 'input_tensor_names': input_tensor_names,
+ 'input_binding_names': input_binding_names,
+ 'verbose': verbose,
+ 'force_engine_update': force_engine_update
+ }]
+ )
+
+ rtdetr_decoder_node = ComposableNode(
+ name='rtdetr_decoder',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrDecoderNode',
+ )
+
+ container = ComposableNodeContainer(
+ name='rtdetr_container',
+ namespace='rtdetr_container',
+ package='rclcpp_components',
+ executable='component_container_mt',
+ composable_node_descriptions=[
+ resize_node, pad_node, image_format_node,
+ image_to_tensor_node, interleave_to_planar_node, reshape_node,
+ rtdetr_preprocessor_node, tensor_rt_node, rtdetr_decoder_node
+ ],
+ output='screen'
+ )
+
+ final_launch_description = launch_args + [container]
+ return launch.LaunchDescription(final_launch_description)
diff --git a/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_core.launch.py b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_core.launch.py
new file mode 100644
index 0000000..15923c4
--- /dev/null
+++ b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_core.launch.py
@@ -0,0 +1,233 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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 typing import Any, Dict
+
+from isaac_ros_examples import IsaacROSLaunchFragment
+import launch
+from launch.actions import DeclareLaunchArgument
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import ComposableNodeContainer
+from launch_ros.descriptions import ComposableNode
+
+MODEL_INPUT_SIZE = 640 # RT-DETR models expect 640x640 encoded image size
+MODEL_NUM_CHANNELS = 3 # RT-DETR models expect 3 image channels
+
+
+class IsaacROSRtDetrLaunchFragment(IsaacROSLaunchFragment):
+
+ @staticmethod
+ def get_composable_nodes(interface_specs: Dict[str, Any]) -> Dict[str, ComposableNode]:
+
+ # RT-DETR parameters
+ confidence_threshold = LaunchConfiguration('confidence_threshold')
+
+ # TensorRT parameters
+ model_file_path = LaunchConfiguration('model_file_path')
+ engine_file_path = LaunchConfiguration('engine_file_path')
+ input_tensor_names = LaunchConfiguration('input_tensor_names')
+ input_binding_names = LaunchConfiguration('input_binding_names')
+ output_tensor_names = LaunchConfiguration('output_tensor_names')
+ output_binding_names = LaunchConfiguration('output_binding_names')
+ verbose = LaunchConfiguration('verbose')
+ force_engine_update = LaunchConfiguration('force_engine_update')
+
+ return {
+ 'resize_node': ComposableNode(
+ name='resize_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ResizeNode',
+ parameters=[{
+ 'input_width': interface_specs['camera_resolution']['width'],
+ 'input_height': interface_specs['camera_resolution']['height'],
+ 'output_width': MODEL_INPUT_SIZE,
+ 'output_height': MODEL_INPUT_SIZE,
+ 'keep_aspect_ratio': True,
+ 'encoding_desired': 'rgb8',
+ 'disable_padding': True
+ }],
+ remappings=[
+ ('image', 'image_rect'),
+ ('camera_info', 'camera_info_rect')
+ ]
+ ),
+ 'pad_node': ComposableNode(
+ name='pad_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::PadNode',
+ parameters=[{
+ 'output_image_width': MODEL_INPUT_SIZE,
+ 'output_image_height': MODEL_INPUT_SIZE,
+ 'padding_type': 'BOTTOM_RIGHT'
+ }],
+ remappings=[(
+ 'image', 'resize/image'
+ )]
+ ),
+ 'image_format_node': ComposableNode(
+ name='image_format_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ImageFormatConverterNode',
+ parameters=[{
+ 'encoding_desired': 'rgb8',
+ 'image_width': MODEL_INPUT_SIZE,
+ 'image_height': MODEL_INPUT_SIZE
+ }],
+ remappings=[
+ ('image_raw', 'padded_image'),
+ ('image', 'image_rgb')]
+ ),
+ 'image_to_tensor_node': ComposableNode(
+ name='image_to_tensor_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ImageToTensorNode',
+ parameters=[{
+ 'scale': False,
+ 'tensor_name': 'image',
+ }],
+ remappings=[
+ ('image', 'image_rgb'),
+ ('tensor', 'normalized_tensor'),
+ ]
+ ),
+ 'interleave_to_planar_node': ComposableNode(
+ name='interleaved_to_planar_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::InterleavedToPlanarNode',
+ parameters=[{
+ 'input_tensor_shape': [MODEL_INPUT_SIZE, MODEL_INPUT_SIZE, MODEL_NUM_CHANNELS]
+ }],
+ remappings=[
+ ('interleaved_tensor', 'normalized_tensor')
+ ]
+ ),
+ 'reshape_node': ComposableNode(
+ name='reshape_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ReshapeNode',
+ parameters=[{
+ 'output_tensor_name': 'input_tensor',
+ 'input_tensor_shape': [MODEL_NUM_CHANNELS, MODEL_INPUT_SIZE, MODEL_INPUT_SIZE],
+ 'output_tensor_shape': [
+ 1, MODEL_NUM_CHANNELS, MODEL_INPUT_SIZE, MODEL_INPUT_SIZE]
+ }],
+ remappings=[
+ ('tensor', 'planar_tensor')
+ ],
+ ),
+ 'rtdetr_preprocessor_node': ComposableNode(
+ name='rtdetr_preprocessor',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode',
+ parameters=[{
+ 'image_width': interface_specs['camera_resolution']['width'],
+ 'image_height': interface_specs['camera_resolution']['height'],
+ }],
+ remappings=[
+ ('encoded_tensor', 'reshaped_tensor')
+ ]
+ ),
+ 'tensor_rt_node': ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ parameters=[{
+ 'model_file_path': model_file_path,
+ 'engine_file_path': engine_file_path,
+ 'output_binding_names': output_binding_names,
+ 'output_tensor_names': output_tensor_names,
+ 'input_tensor_names': input_tensor_names,
+ 'input_binding_names': input_binding_names,
+ 'verbose': verbose,
+ 'force_engine_update': force_engine_update
+ }]
+ ),
+ 'rtdetr_decoder_node': ComposableNode(
+ name='rtdetr_decoder',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrDecoderNode',
+ parameters=[{
+ 'confidence_threshold': confidence_threshold
+ }]
+ )
+ }
+
+ @staticmethod
+ def get_launch_actions(interface_specs: Dict[str, Any]) -> \
+ Dict[str, launch.actions.OpaqueFunction]:
+ return {
+ 'model_file_path': DeclareLaunchArgument(
+ 'model_file_path',
+ default_value='',
+ description='The absolute file path to the ONNX file'
+ ),
+ 'engine_file_path': DeclareLaunchArgument(
+ 'engine_file_path',
+ default_value='',
+ description='The absolute file path to the TensorRT engine file'
+ ),
+ 'input_tensor_names': DeclareLaunchArgument(
+ 'input_tensor_names',
+ default_value='["images", "orig_target_sizes"]',
+ description='A list of tensor names to bound to the specified input binding names'
+ ),
+ 'input_binding_names': DeclareLaunchArgument(
+ 'input_binding_names',
+ default_value='["images", "orig_target_sizes"]',
+ description='A list of input tensor binding names (specified by model)'
+ ),
+ 'output_tensor_names': DeclareLaunchArgument(
+ 'output_tensor_names',
+ default_value='["labels", "boxes", "scores"]',
+ description='A list of tensor names to bound to the specified output binding names'
+ ),
+ 'output_binding_names': DeclareLaunchArgument(
+ 'output_binding_names',
+ default_value='["labels", "boxes", "scores"]',
+ description='A list of output tensor binding names (specified by model)'
+ ),
+ 'verbose': DeclareLaunchArgument(
+ 'verbose',
+ default_value='False',
+ description='Whether TensorRT should verbosely log or not'
+ ),
+ 'force_engine_update': DeclareLaunchArgument(
+ 'force_engine_update',
+ default_value='False',
+ description='Whether TensorRT should update the TensorRT engine file or not'
+ ),
+ 'confidence_threshold': DeclareLaunchArgument(
+ 'confidence_threshold',
+ default_value='0.9',
+ description='The minimum confidence threshold for detections'
+ ),
+ }
+
+
+def generate_launch_description():
+ rtdetr_container = ComposableNodeContainer(
+ package='rclcpp_components',
+ name='rtdetr_container',
+ namespace='',
+ executable='component_container_mt',
+ composable_node_descriptions=IsaacROSRtDetrLaunchFragment
+ .get_composable_nodes().values(),
+ output='screen'
+ )
+
+ return launch.LaunchDescription(
+ [rtdetr_container] + IsaacROSRtDetrLaunchFragment.get_launch_actions().values())
diff --git a/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_isaac_sim.launch.py b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_isaac_sim.launch.py
new file mode 100644
index 0000000..8ab537a
--- /dev/null
+++ b/isaac_ros_rtdetr/launch/isaac_ros_rtdetr_isaac_sim.launch.py
@@ -0,0 +1,207 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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 launch
+from launch.actions import DeclareLaunchArgument
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import ComposableNodeContainer, Node
+from launch_ros.descriptions import ComposableNode
+
+
+RT_DETR_MODEL_INPUT_SIZE = 640 # RT-DETR models expect 640x640 encoded image size
+RT_DETR_MODEL_NUM_CHANNELS = 3 # RT-DETR models expect 3 image channels
+
+ESS_MODEL_IMAGE_WIDTH = 480
+ESS_MODEL_IMAGE_HEIGHT = 288
+
+SIM_IMAGE_WIDTH = 1920
+SIM_IMAGE_HEIGHT = 1200
+
+SIM_TO_RT_DETR_RATIO = SIM_IMAGE_WIDTH / RT_DETR_MODEL_INPUT_SIZE
+
+ISAAC_ROS_ASSETS_PATH = os.path.join(os.environ['ISAAC_ROS_WS'], 'isaac_ros_assets')
+ISAAC_ROS_MODELS_PATH = os.path.join(ISAAC_ROS_ASSETS_PATH, 'models')
+SYNTHETICA_DETR_MODELS_PATH = os.path.join(ISAAC_ROS_MODELS_PATH, 'synthetica_detr')
+RTDETR_ENGINE_PATH = os.path.join(SYNTHETICA_DETR_MODELS_PATH, 'sdetr_grasp.plan')
+
+
+def generate_launch_description():
+ """Generate launch description for testing relevant nodes."""
+ launch_args = [
+ DeclareLaunchArgument(
+ 'rt_detr_engine_file_path',
+ default_value=RTDETR_ENGINE_PATH,
+ description='The absolute file path to the RT-DETR TensorRT engine file'),
+
+ DeclareLaunchArgument(
+ 'ess_depth_threshold',
+ default_value='0.35',
+ description='Threshold value ranges between 0.0 and 1.0 '
+ 'for filtering disparity with confidence.'),
+
+ DeclareLaunchArgument(
+ 'container_name',
+ default_value='foundationpose_container',
+ description='Name for ComposableNodeContainer'),
+ ]
+
+ rt_detr_engine_file_path = LaunchConfiguration('rt_detr_engine_file_path')
+ container_name = LaunchConfiguration('container_name')
+
+ # Resize and pad Isaac Sim images to RT-DETR model input image size
+ resize_left_rt_detr_node = ComposableNode(
+ name='resize_left_rt_detr_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ResizeNode',
+ parameters=[{
+ 'input_width': SIM_IMAGE_WIDTH,
+ 'input_height': SIM_IMAGE_HEIGHT,
+ 'output_width': RT_DETR_MODEL_INPUT_SIZE,
+ 'output_height': RT_DETR_MODEL_INPUT_SIZE,
+ 'keep_aspect_ratio': True,
+ 'encoding_desired': 'rgb8',
+ 'disable_padding': True
+ }],
+ remappings=[
+ ('image', 'front_stereo_camera/left_rgb/image_raw'),
+ ('camera_info', 'front_stereo_camera/left_rgb/camerainfo')
+ ]
+ )
+ pad_node = ComposableNode(
+ name='pad_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::PadNode',
+ parameters=[{
+ 'output_image_width': RT_DETR_MODEL_INPUT_SIZE,
+ 'output_image_height': RT_DETR_MODEL_INPUT_SIZE,
+ 'padding_type': 'BOTTOM_RIGHT'
+ }],
+ remappings=[(
+ 'image', 'resize/image'
+ )]
+ )
+
+ # Convert image to tensor and reshape
+ image_to_tensor_node = ComposableNode(
+ name='image_to_tensor_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ImageToTensorNode',
+ parameters=[{
+ 'scale': False,
+ 'tensor_name': 'image',
+ }],
+ remappings=[
+ ('image', 'padded_image'),
+ ('tensor', 'normalized_tensor'),
+ ]
+ )
+ interleave_to_planar_node = ComposableNode(
+ name='interleaved_to_planar_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::InterleavedToPlanarNode',
+ parameters=[{
+ 'input_tensor_shape': [RT_DETR_MODEL_INPUT_SIZE,
+ RT_DETR_MODEL_INPUT_SIZE,
+ RT_DETR_MODEL_NUM_CHANNELS]
+ }],
+ remappings=[
+ ('interleaved_tensor', 'normalized_tensor')
+ ]
+ )
+ reshape_node = ComposableNode(
+ name='reshape_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ReshapeNode',
+ parameters=[{
+ 'output_tensor_name': 'input_tensor',
+ 'input_tensor_shape': [RT_DETR_MODEL_NUM_CHANNELS,
+ RT_DETR_MODEL_INPUT_SIZE,
+ RT_DETR_MODEL_INPUT_SIZE],
+ 'output_tensor_shape': [1, RT_DETR_MODEL_NUM_CHANNELS,
+ RT_DETR_MODEL_INPUT_SIZE,
+ RT_DETR_MODEL_INPUT_SIZE]
+ }],
+ remappings=[
+ ('tensor', 'planar_tensor')
+ ],
+ )
+ rtdetr_preprocessor_node = ComposableNode(
+ name='rtdetr_preprocessor',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode',
+ remappings=[
+ ('encoded_tensor', 'reshaped_tensor')
+ ]
+ )
+
+ # RT-DETR objection detection pipeline
+ tensor_rt_node = ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ parameters=[{
+ 'engine_file_path': rt_detr_engine_file_path,
+ 'output_binding_names': ['labels', 'boxes', 'scores'],
+ 'output_tensor_names': ['labels', 'boxes', 'scores'],
+ 'input_tensor_names': ['images', 'orig_target_sizes'],
+ 'input_binding_names': ['images', 'orig_target_sizes'],
+ 'force_engine_update': False
+ }]
+ )
+ rtdetr_decoder_node = ComposableNode(
+ name='rtdetr_decoder',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrDecoderNode',
+ )
+
+ isaac_ros_rtdetr_visualizer_node = Node(
+ package='isaac_ros_rtdetr',
+ executable='isaac_ros_rtdetr_visualizer.py',
+ name='isaac_ros_rtdetr_visualizer',
+ remappings=[
+ ('image_rect', 'resize/image')
+ ])
+
+ rqt_image_view_node = Node(
+ package='rqt_image_view',
+ executable='rqt_image_view',
+ name='rqt_image_view',
+ arguments=['/rtdetr_processed_image'])
+
+ rtdetr_container = ComposableNodeContainer(
+ name=container_name,
+ namespace='',
+ package='rclcpp_components',
+ executable='component_container_mt',
+ composable_node_descriptions=[
+ resize_left_rt_detr_node,
+ pad_node,
+ image_to_tensor_node,
+ interleave_to_planar_node,
+ reshape_node,
+ rtdetr_preprocessor_node,
+ tensor_rt_node,
+ rtdetr_decoder_node,
+ ],
+ output='screen'
+ )
+
+ return launch.LaunchDescription(launch_args + [rtdetr_container,
+ isaac_ros_rtdetr_visualizer_node,
+ rqt_image_view_node])
diff --git a/isaac_ros_rtdetr/package.xml b/isaac_ros_rtdetr/package.xml
new file mode 100644
index 0000000..11e8ebe
--- /dev/null
+++ b/isaac_ros_rtdetr/package.xml
@@ -0,0 +1,56 @@
+
+
+
+
+
+
+ isaac_ros_rtdetr
+ 3.0.0
+ RT-DETR model processing
+
+ Isaac ROS Maintainers
+ Apache-2.0
+ https://developer.nvidia.com/isaac-ros/
+ Jaiveer Singh
+
+ ament_cmake_auto
+
+ rclcpp
+ rclcpp_components
+ vision_msgs
+ isaac_ros_nitros
+ isaac_ros_nitros_tensor_list_type
+ isaac_ros_managed_nitros
+ isaac_ros_tensor_list_interfaces
+
+ isaac_ros_common
+
+ isaac_ros_dnn_image_encoder
+ isaac_ros_image_proc
+ isaac_ros_tensor_rt
+ gxf_isaac_optimizer
+
+ ament_lint_auto
+ ament_lint_common
+ isaac_ros_test
+
+
+ ament_cmake
+
+
diff --git a/isaac_ros_rtdetr/scripts/isaac_ros_rtdetr_visualizer.py b/isaac_ros_rtdetr/scripts/isaac_ros_rtdetr_visualizer.py
new file mode 100755
index 0000000..3494e04
--- /dev/null
+++ b/isaac_ros_rtdetr/scripts/isaac_ros_rtdetr_visualizer.py
@@ -0,0 +1,95 @@
+#!/usr/bin/env python3
+
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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 script listens for images and object detections on the image,
+# then renders the output boxes on top of the image and publishes
+# the result as an image message
+
+import cv2
+import cv_bridge
+import message_filters
+import rclpy
+from rclpy.node import Node
+from sensor_msgs.msg import Image
+from vision_msgs.msg import Detection2DArray
+
+
+class RtDetrVisualizer(Node):
+ QUEUE_SIZE = 10
+ color = (0, 255, 0)
+ bbox_thickness = 1
+ font = cv2.FONT_HERSHEY_SIMPLEX
+ font_scale = 0.5
+ line_type = 2
+
+ def __init__(self):
+ super().__init__('rtdetr_visualizer')
+ self._bridge = cv_bridge.CvBridge()
+ self._processed_image_pub = self.create_publisher(
+ Image, 'rtdetr_processed_image', self.QUEUE_SIZE)
+
+ self._detections_subscription = message_filters.Subscriber(
+ self,
+ Detection2DArray,
+ 'detections_output')
+ self._image_subscription = message_filters.Subscriber(
+ self,
+ Image,
+ 'image_rect')
+
+ self.time_synchronizer = message_filters.TimeSynchronizer(
+ [self._detections_subscription, self._image_subscription],
+ self.QUEUE_SIZE)
+
+ self.time_synchronizer.registerCallback(self.detections_callback)
+
+ def detections_callback(self, detections_msg, img_msg):
+ cv2_img = self._bridge.imgmsg_to_cv2(img_msg)
+ for detection in detections_msg.detections:
+ center_x = detection.bbox.center.position.x
+ center_y = detection.bbox.center.position.y
+ width = detection.bbox.size_x
+ height = detection.bbox.size_y
+
+ try:
+ min_pt = (round(center_x - (width / 2.0)), round(center_y - (height / 2.0)))
+ max_pt = (round(center_x + (width / 2.0)), round(center_y + (height / 2.0)))
+
+ cv2.rectangle(cv2_img, min_pt, max_pt, self.color, self.bbox_thickness)
+
+ cv2.putText(cv2_img, detection.results[0].hypothesis.class_id,
+ min_pt, self.font, self.font_scale, self.color, self.line_type)
+
+ except ValueError:
+ # Ignore NaNs that may be produced when calculating the bounding box
+ pass
+
+ processed_img = self._bridge.cv2_to_imgmsg(
+ cv2_img, encoding=img_msg.encoding)
+ self._processed_image_pub.publish(processed_img)
+
+
+def main():
+ rclpy.init()
+ rclpy.spin(RtDetrVisualizer())
+ rclpy.shutdown()
+
+
+if __name__ == '__main__':
+ main()
diff --git a/isaac_ros_rtdetr/src/rtdetr_decoder_node.cpp b/isaac_ros_rtdetr/src/rtdetr_decoder_node.cpp
new file mode 100644
index 0000000..b1d3f91
--- /dev/null
+++ b/isaac_ros_rtdetr/src/rtdetr_decoder_node.cpp
@@ -0,0 +1,132 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2024 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 "isaac_ros_rtdetr/rtdetr_decoder_node.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+namespace rtdetr
+{
+namespace
+{
+
+template
+std::vector TensorToVector(
+ const nvidia::isaac_ros::nitros::NitrosTensorListView & tensor_list,
+ const std::string & tensor_name, cudaStream_t stream)
+{
+ auto tensor = tensor_list.GetNamedTensor(tensor_name);
+ std::vector vector(tensor.GetElementCount());
+ cudaMemcpyAsync(
+ vector.data(), tensor.GetBuffer(),
+ tensor.GetTensorSize(), cudaMemcpyDefault, stream);
+ return vector;
+}
+
+} // namespace
+
+RtDetrDecoderNode::RtDetrDecoderNode(const rclcpp::NodeOptions options)
+: rclcpp::Node("rtdetr_decoder_node", options),
+ nitros_sub_{std::make_shared>(
+ this,
+ "tensor_sub",
+ nvidia::isaac_ros::nitros::nitros_tensor_list_nchw_rgb_f32_t::supported_type_name,
+ std::bind(&RtDetrDecoderNode::InputCallback, this,
+ std::placeholders::_1))},
+ pub_{create_publisher(
+ "detections_output", 10)},
+ labels_tensor_name_{declare_parameter(
+ "labels_tensor_name",
+ "labels")},
+ boxes_tensor_name_{declare_parameter(
+ "boxes_tensor_name",
+ "boxes")},
+ scores_tensor_name_{declare_parameter(
+ "scores_tensor_name",
+ "scores")},
+ confidence_threshold_{declare_parameter("confidence_threshold", 0.9)}
+{
+ cudaStreamCreate(&stream_);
+}
+
+RtDetrDecoderNode::~RtDetrDecoderNode()
+{
+ cudaStreamDestroy(stream_);
+}
+
+void RtDetrDecoderNode::InputCallback(
+ const nvidia::isaac_ros::nitros::NitrosTensorListView & msg)
+{
+ // Bring labels, boxes, and scores back to CPU
+ auto labels = TensorToVector(msg, labels_tensor_name_, stream_);
+ auto boxes = TensorToVector(msg, boxes_tensor_name_, stream_);
+ auto scores = TensorToVector(msg, scores_tensor_name_, stream_);
+ cudaStreamSynchronize(stream_);
+
+ std_msgs::msg::Header header{};
+ header.stamp.sec = msg.GetTimestampSeconds();
+ header.stamp.nanosec = msg.GetTimestampNanoseconds();
+ header.frame_id = msg.GetFrameId();
+
+ vision_msgs::msg::Detection2DArray detections;
+ detections.header = header;
+
+ for (size_t i = 0; i < scores.size(); ++i) {
+ // Filter out low-confidence detections
+ if (scores.at(i) <= confidence_threshold_) {
+ continue;
+ }
+
+ vision_msgs::msg::Detection2D detection;
+ detection.header = header;
+
+ // Save score and label
+ vision_msgs::msg::ObjectHypothesisWithPose hyp;
+ hyp.hypothesis.class_id = std::to_string(labels.at(i));
+ hyp.hypothesis.score = scores.at(i);
+ detection.results.push_back(hyp);
+
+ // Convert (x1, y1, x2, y2) format into (cx, cy, w, h)
+ // Each bounding box is stored as 4 contiguous numbers
+ constexpr size_t BOX_SIZE = 4;
+ float x1 = boxes.at(BOX_SIZE * i);
+ float y1 = boxes.at(BOX_SIZE * i + 1);
+ float x2 = boxes.at(BOX_SIZE * i + 2);
+ float y2 = boxes.at(BOX_SIZE * i + 3);
+
+ detection.bbox.center.position.x = (x1 + x2) / 2;
+ detection.bbox.center.position.y = (y1 + y2) / 2;
+ detection.bbox.size_x = (x2 - x1);
+ detection.bbox.size_y = (y2 - y1);
+
+ // Add detection to output array
+ detections.detections.push_back(detection);
+ }
+
+ pub_->publish(detections);
+}
+
+} // namespace rtdetr
+} // namespace isaac_ros
+} // namespace nvidia
+
+// Register as component
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(nvidia::isaac_ros::rtdetr::RtDetrDecoderNode)
diff --git a/isaac_ros_rtdetr/src/rtdetr_preprocessor_node.cpp b/isaac_ros_rtdetr/src/rtdetr_preprocessor_node.cpp
new file mode 100644
index 0000000..dcfaced
--- /dev/null
+++ b/isaac_ros_rtdetr/src/rtdetr_preprocessor_node.cpp
@@ -0,0 +1,126 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2024 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 "isaac_ros_rtdetr/rtdetr_preprocessor_node.hpp"
+
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_builder.hpp"
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list.hpp"
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_builder.hpp"
+#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+namespace rtdetr
+{
+
+
+RtDetrPreprocessorNode::RtDetrPreprocessorNode(const rclcpp::NodeOptions options)
+: rclcpp::Node("rtdetr_preprocessor_node", options),
+ nitros_sub_{std::make_shared>(
+ this,
+ "encoded_tensor",
+ nvidia::isaac_ros::nitros::nitros_tensor_list_nchw_rgb_f32_t::supported_type_name,
+ std::bind(&RtDetrPreprocessorNode::InputCallback, this,
+ std::placeholders::_1))},
+ nitros_pub_{std::make_shared>(
+ this,
+ "tensor_pub",
+ nvidia::isaac_ros::nitros::nitros_tensor_list_nchw_rgb_f32_t::supported_type_name)},
+ input_image_tensor_name_{declare_parameter(
+ "input_image_tensor_name",
+ "input_tensor")},
+ output_image_tensor_name_{declare_parameter("output_image_tensor_name", "images")},
+ output_size_tensor_name_{declare_parameter(
+ "output_size_tensor_name",
+ "orig_target_sizes")},
+ image_height_{declare_parameter("image_height", 480)},
+ image_width_{declare_parameter("image_width", 640)}
+{
+ cudaStreamCreate(&stream_);
+}
+
+RtDetrPreprocessorNode::~RtDetrPreprocessorNode()
+{
+ cudaStreamDestroy(stream_);
+}
+
+void RtDetrPreprocessorNode::InputCallback(
+ const nvidia::isaac_ros::nitros::NitrosTensorListView & msg)
+{
+ // Forward header from input message
+ std_msgs::msg::Header header{};
+ header.stamp.sec = msg.GetTimestampSeconds();
+ header.stamp.nanosec = msg.GetTimestampNanoseconds();
+ header.frame_id = msg.GetFrameId();
+
+ // Fetch input encoded image, perform preprocessing, then forward to output
+ auto input_image_tensor = msg.GetNamedTensor(input_image_tensor_name_);
+ float * output_image_buffer;
+ cudaMallocAsync(&output_image_buffer, input_image_tensor.GetTensorSize(), stream_);
+ cudaMemcpyAsync(
+ output_image_buffer, input_image_tensor.GetBuffer(),
+ input_image_tensor.GetTensorSize(), cudaMemcpyDefault, stream_);
+
+ // The model only requires the larger of the 2 dimensions.
+ // Narrowing conversion required because model expects int32_t, but ROS 2 only supports int64_t
+ int32_t image_size = static_cast(std::max(image_height_, image_width_));
+ int32_t output_size[2]{image_size, image_size};
+ void * output_size_buffer;
+ cudaMallocAsync(&output_size_buffer, sizeof(output_size), stream_);
+ cudaMemcpyAsync(output_size_buffer, output_size, sizeof(output_size), cudaMemcpyDefault, stream_);
+ cudaStreamSynchronize(stream_);
+
+ // Compose new output tensor list that contains encoded image and target size
+ auto output_tensor_list =
+ nvidia::isaac_ros::nitros::NitrosTensorListBuilder()
+ .WithHeader(header)
+ .AddTensor(
+ output_image_tensor_name_,
+ (
+ nvidia::isaac_ros::nitros::NitrosTensorBuilder()
+ .WithShape(input_image_tensor.GetShape())
+ .WithDataType(nvidia::isaac_ros::nitros::NitrosDataType::kFloat32)
+ .WithData(output_image_buffer)
+ .Build()
+ )
+ )
+ .AddTensor(
+ output_size_tensor_name_,
+ (
+ nvidia::isaac_ros::nitros::NitrosTensorBuilder()
+ .WithShape({1, 2})
+ .WithDataType(nvidia::isaac_ros::nitros::NitrosDataType::kInt32)
+ .WithData(output_size_buffer)
+ .Build()
+ )
+ )
+ .Build();
+
+ nitros_pub_->publish(output_tensor_list);
+}
+
+} // namespace rtdetr
+} // namespace isaac_ros
+} // namespace nvidia
+
+// Register as component
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode)
diff --git a/isaac_ros_rtdetr/test/dummy_model/rtdetr_dummy_pol.onnx b/isaac_ros_rtdetr/test/dummy_model/rtdetr_dummy_pol.onnx
new file mode 100644
index 0000000..f28919e
--- /dev/null
+++ b/isaac_ros_rtdetr/test/dummy_model/rtdetr_dummy_pol.onnx
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:3b09bb405b359b3cf8f6ea718621726cb1c850d572ad2bb82ca8b450c6b1d11f
+size 4933199
diff --git a/isaac_ros_rtdetr/test/isaac_ros_rtdetr_pol_test.py b/isaac_ros_rtdetr/test/isaac_ros_rtdetr_pol_test.py
new file mode 100644
index 0000000..1aad664
--- /dev/null
+++ b/isaac_ros_rtdetr/test/isaac_ros_rtdetr_pol_test.py
@@ -0,0 +1,257 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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
+
+"""
+Proof-Of-Life test for the Isaac ROS RT-DETR package.
+
+ 1. Sets up DnnImageEncoderNode, RtDetrPreprocessorNode, TensorRTNode, RtDetrDecoderNode
+ 2. Loads a sample image and publishes it
+ 3. Subscribes to the relevant topics, waiting for an output from RtDetrDecoderNode
+ 4. Verifies that the received output sizes and encodings are correct (based on dummy model)
+
+ Note: the data is not verified because the model is initialized with random weights
+"""
+
+
+import os
+import pathlib
+import time
+
+from isaac_ros_test import IsaacROSBaseTest, JSONConversion
+from launch_ros.actions.composable_node_container import ComposableNodeContainer
+from launch_ros.descriptions.composable_node import ComposableNode
+
+import pytest
+import rclpy
+
+from sensor_msgs.msg import CameraInfo, Image
+from vision_msgs.msg import Detection2DArray
+
+MODEL_FILE_NAME = 'rtdetr_dummy_pol.onnx'
+
+MODEL_GENERATION_TIMEOUT_SEC = 300
+INIT_WAIT_SEC = 10
+MODEL_PATH = '/tmp/rtdetr_dummy_pol.plan'
+
+
+@pytest.mark.rostest
+def generate_test_description():
+ """Generate launch description for testing relevant nodes."""
+ resize_node = ComposableNode(
+ name='resize_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ResizeNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'input_width': 640,
+ 'input_height': 480,
+ 'output_width': 640,
+ 'output_height': 640,
+ 'keep_aspect_ratio': True,
+ 'encoding_desired': 'rgb8',
+ 'disable_padding': True
+ }]
+ )
+
+ pad_node = ComposableNode(
+ name='pad_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::PadNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'output_image_width': 640,
+ 'output_image_height': 640,
+ 'padding_type': 'BOTTOM_RIGHT'
+ }],
+ remappings=[(
+ 'image', 'resize/image'
+ )]
+ )
+
+ image_format_node = ComposableNode(
+ name='image_format_node',
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ImageFormatConverterNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'encoding_desired': 'rgb8',
+ 'image_width': 640,
+ 'image_height': 640
+ }],
+ remappings=[
+ ('image_raw', 'padded_image'),
+ ('image', 'image_rgb')]
+ )
+
+ image_to_tensor_node = ComposableNode(
+ name='image_to_tensor_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ImageToTensorNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'scale': False,
+ 'tensor_name': 'image',
+ }],
+ remappings=[
+ ('image', 'image_rgb'),
+ ('tensor', 'normalized_tensor'),
+ ]
+ )
+
+ interleave_to_planar_node = ComposableNode(
+ name='interleaved_to_planar_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::InterleavedToPlanarNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'input_tensor_shape': [640, 640, 3]
+ }],
+ remappings=[
+ ('interleaved_tensor', 'normalized_tensor')
+ ]
+ )
+
+ reshape_node = ComposableNode(
+ name='reshape_node',
+ package='isaac_ros_tensor_proc',
+ plugin='nvidia::isaac_ros::dnn_inference::ReshapeNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'output_tensor_name': 'input_tensor',
+ 'input_tensor_shape': [3, 640, 640],
+ 'output_tensor_shape': [1, 3, 640, 640]
+ }],
+ remappings=[
+ ('tensor', 'planar_tensor')
+ ],
+ )
+
+ rtdetr_preprocessor_node = ComposableNode(
+ name='rtdetr_preprocessor',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrPreprocessorNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ remappings=[
+ ('encoded_tensor', 'reshaped_tensor')
+ ],
+ )
+
+ tensor_rt_node = ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace(),
+ parameters=[{
+ 'model_file_path': f'{os.path.dirname(__file__)}/dummy_model/{MODEL_FILE_NAME}',
+ 'engine_file_path': MODEL_PATH,
+ 'input_tensor_names': ['images', 'orig_target_sizes'],
+ 'input_binding_names': ['images', 'orig_target_sizes'],
+ 'output_binding_names': ['labels', 'boxes', 'scores'],
+ 'output_tensor_names': ['labels', 'boxes', 'scores'],
+ 'verbose': False,
+ 'force_engine_update': False
+ }]
+ )
+
+ rtdetr_decoder_node = ComposableNode(
+ name='rtdetr_decoder',
+ package='isaac_ros_rtdetr',
+ plugin='nvidia::isaac_ros::rtdetr::RtDetrDecoderNode',
+ namespace=IsaacROSRtDetrPOLTest.generate_namespace()
+ )
+
+ container = ComposableNodeContainer(
+ name='rtdetr_container',
+ namespace='rtdetr_container',
+ package='rclcpp_components',
+ executable='component_container_mt',
+ composable_node_descriptions=[
+ resize_node, pad_node, image_format_node,
+ image_to_tensor_node, interleave_to_planar_node, reshape_node,
+ rtdetr_preprocessor_node, tensor_rt_node, rtdetr_decoder_node
+ ],
+ output='screen'
+ )
+
+ return IsaacROSRtDetrPOLTest.generate_test_description([container])
+
+
+class IsaacROSRtDetrPOLTest(IsaacROSBaseTest):
+ """Validates that the inference pipeline produces outputs using a RT-DETR-like dummy model."""
+
+ # filepath is required by IsaacROSBaseTest
+ filepath = pathlib.Path(os.path.dirname(__file__))
+ INIT_WAIT_SEC = 10
+
+ @IsaacROSBaseTest.for_each_test_case()
+ def test_object_detection(self, test_folder):
+ """Expect the node to produce detection array given image."""
+ self.node._logger.info(f'Generating model (timeout={MODEL_GENERATION_TIMEOUT_SEC}s)')
+ start_time = time.time()
+ wait_cycles = 1
+ while not os.path.isfile(MODEL_PATH):
+ time_diff = time.time() - start_time
+ if time_diff > MODEL_GENERATION_TIMEOUT_SEC:
+ self.fail('Model generation timed out')
+ if time_diff > wait_cycles*10:
+ self.node._logger.info(
+ f'Waiting for model generation to finish... ({time_diff:.0f}s passed)')
+ wait_cycles += 1
+ time.sleep(1)
+
+ self.node._logger.info(
+ f'Model generation was finished (took {(time.time() - start_time)}s)')
+
+ received_messages = {}
+
+ self.generate_namespace_lookup(['image', 'camera_info', 'detections_output'])
+
+ image_pub = self.node.create_publisher(
+ Image, self.namespaces['image'], self.DEFAULT_QOS)
+ camera_info_pub = self.node.create_publisher(
+ CameraInfo, self.namespaces['camera_info'], self.DEFAULT_QOS)
+ subs = self.create_logging_subscribers(
+ [('detections_output', Detection2DArray)], received_messages)
+
+ try:
+ image = JSONConversion.load_image_from_json(
+ test_folder / 'image.json')
+ camera_info = JSONConversion.load_camera_info_from_json(
+ test_folder / 'camera_info.json')
+ timestamp = self.node.get_clock().now().to_msg()
+ image.header.stamp = timestamp
+ camera_info.header.stamp = timestamp
+
+ TIMEOUT = 60
+ end_time = time.time() + TIMEOUT
+ done = False
+
+ while time.time() < end_time:
+ image_pub.publish(image)
+ camera_info_pub.publish(camera_info)
+ rclpy.spin_once(self.node, timeout_sec=0.1)
+
+ if 'detections_output' in received_messages:
+ done = True
+ break
+
+ self.assertTrue(
+ done, "Didn't receive output on detections_output topic!")
+
+ finally:
+ self.node.destroy_subscription(subs)
+ self.node.destroy_publisher(image_pub)
diff --git a/isaac_ros_rtdetr/test/test_cases/single_detection/camera_info.json b/isaac_ros_rtdetr/test/test_cases/single_detection/camera_info.json
new file mode 100644
index 0000000..08fbe98
--- /dev/null
+++ b/isaac_ros_rtdetr/test/test_cases/single_detection/camera_info.json
@@ -0,0 +1,51 @@
+{
+ "header": {
+ "frame_id": "tf_camera"
+ },
+ "width": 640,
+ "height": 480,
+ "distortion_model": "plumb_bob",
+ "D": [
+ 0.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 0.0
+ ],
+ "K": [
+ 651.2994384765625,
+ 0.000000,
+ 298.3225504557292,
+ 0.0,
+ 651.2994384765625,
+ 392.1635182698568,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "R": [
+ 1.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "P": [
+ 1.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0,
+ 0.0
+ ]
+}
\ No newline at end of file
diff --git a/isaac_ros_rtdetr/test/test_cases/single_detection/color_000000.jpg b/isaac_ros_rtdetr/test/test_cases/single_detection/color_000000.jpg
new file mode 100644
index 0000000..97e7367
--- /dev/null
+++ b/isaac_ros_rtdetr/test/test_cases/single_detection/color_000000.jpg
@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:84b21f989fca7b98ca4cfb902346401a0c2d917cff2fbf4f207bad98b30bbdd1
+size 103786
diff --git a/isaac_ros_rtdetr/test/test_cases/single_detection/image.json b/isaac_ros_rtdetr/test/test_cases/single_detection/image.json
new file mode 100644
index 0000000..90e5d58
--- /dev/null
+++ b/isaac_ros_rtdetr/test/test_cases/single_detection/image.json
@@ -0,0 +1,4 @@
+{
+ "image": "color_000000.jpg",
+ "encoding": "bgr8"
+}
\ No newline at end of file
diff --git a/isaac_ros_yolov8/CMakeLists.txt b/isaac_ros_yolov8/CMakeLists.txt
index 206d844..e48fdc9 100644
--- a/isaac_ros_yolov8/CMakeLists.txt
+++ b/isaac_ros_yolov8/CMakeLists.txt
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
@@ -38,6 +38,10 @@ find_package(ament_cmake_python REQUIRED)
ament_auto_add_library(yolov8_decoder_node SHARED src/yolov8_decoder_node.cpp)
rclcpp_components_register_nodes(yolov8_decoder_node "nvidia::isaac_ros::yolov8::YoloV8DecoderNode")
set(node_plugins "${node_plugins}nvidia::isaac_ros::yolov8::YoloV8DecoderNode;$\n")
+set_target_properties(yolov8_decoder_node PROPERTIES
+ BUILD_WITH_INSTALL_RPATH TRUE
+ BUILD_RPATH_USE_ORIGIN TRUE
+ INSTALL_RPATH_USE_LINK_PATH TRUE)
target_link_libraries(yolov8_decoder_node ${OpenCV_LIBRARIES})
diff --git a/isaac_ros_yolov8/include/isaac_ros_yolov8/yolov8_decoder_node.hpp b/isaac_ros_yolov8/include/isaac_ros_yolov8/yolov8_decoder_node.hpp
index b3f586c..d2e59c3 100644
--- a/isaac_ros_yolov8/include/isaac_ros_yolov8/yolov8_decoder_node.hpp
+++ b/isaac_ros_yolov8/include/isaac_ros_yolov8/yolov8_decoder_node.hpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2023-2024 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.
diff --git a/isaac_ros_yolov8/isaac_ros_yolov8/__init__.py b/isaac_ros_yolov8/isaac_ros_yolov8/__init__.py
index 6bbcb13..41b7387 100644
--- a/isaac_ros_yolov8/isaac_ros_yolov8/__init__.py
+++ b/isaac_ros_yolov8/isaac_ros_yolov8/__init__.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
diff --git a/isaac_ros_yolov8/launch/isaac_ros_yolov8_core.launch.py b/isaac_ros_yolov8/launch/isaac_ros_yolov8_core.launch.py
new file mode 100644
index 0000000..afafc40
--- /dev/null
+++ b/isaac_ros_yolov8/launch/isaac_ros_yolov8_core.launch.py
@@ -0,0 +1,195 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2023-2024 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
+from typing import Any, Dict
+
+from ament_index_python.packages import get_package_share_directory
+from isaac_ros_examples import IsaacROSLaunchFragment
+import launch
+
+from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import ComposableNodeContainer
+from launch_ros.descriptions import ComposableNode
+
+
+class IsaacROSYolov8LaunchFragment(IsaacROSLaunchFragment):
+
+ @staticmethod
+ def get_composable_nodes(interface_specs: Dict[str, Any]) -> Dict[str, ComposableNode]:
+
+ # TensorRT parameters
+ model_file_path = LaunchConfiguration('model_file_path')
+ engine_file_path = LaunchConfiguration('engine_file_path')
+ input_tensor_names = LaunchConfiguration('input_tensor_names')
+ input_binding_names = LaunchConfiguration('input_binding_names')
+ output_tensor_names = LaunchConfiguration('output_tensor_names')
+ output_binding_names = LaunchConfiguration('output_binding_names')
+ verbose = LaunchConfiguration('verbose')
+ force_engine_update = LaunchConfiguration('force_engine_update')
+
+ # YOLOv8 Decoder parameters
+ confidence_threshold = LaunchConfiguration('confidence_threshold')
+ nms_threshold = LaunchConfiguration('nms_threshold')
+
+ return {
+ 'tensor_rt_node': ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ parameters=[{
+ 'model_file_path': model_file_path,
+ 'engine_file_path': engine_file_path,
+ 'output_binding_names': output_binding_names,
+ 'output_tensor_names': output_tensor_names,
+ 'input_tensor_names': input_tensor_names,
+ 'input_binding_names': input_binding_names,
+ 'verbose': verbose,
+ 'force_engine_update': force_engine_update
+ }]
+ ),
+ 'yolov8_decoder_node': ComposableNode(
+ name='yolov8_decoder_node',
+ package='isaac_ros_yolov8',
+ plugin='nvidia::isaac_ros::yolov8::YoloV8DecoderNode',
+ parameters=[{
+ 'confidence_threshold': confidence_threshold,
+ 'nms_threshold': nms_threshold,
+ }]
+ )
+ }
+
+ @staticmethod
+ def get_launch_actions(interface_specs: Dict[str, Any]) -> \
+ Dict[str, launch.actions.OpaqueFunction]:
+
+ network_image_width = LaunchConfiguration('network_image_width')
+ network_image_height = LaunchConfiguration('network_image_height')
+ image_mean = LaunchConfiguration('image_mean')
+ image_stddev = LaunchConfiguration('image_stddev')
+
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+
+ return {
+ 'network_image_width': DeclareLaunchArgument(
+ 'network_image_width',
+ default_value='640',
+ description='The input image width that the network expects'
+ ),
+ 'network_image_height': DeclareLaunchArgument(
+ 'network_image_height',
+ default_value='640',
+ description='The input image height that the network expects'
+ ),
+ 'image_mean': DeclareLaunchArgument(
+ 'image_mean',
+ default_value='[0.0, 0.0, 0.0]',
+ description='The mean for image normalization'
+ ),
+ 'image_stddev': DeclareLaunchArgument(
+ 'image_stddev',
+ default_value='[1.0, 1.0, 1.0]',
+ description='The standard deviation for image normalization'
+ ),
+ 'model_file_path': DeclareLaunchArgument(
+ 'model_file_path',
+ default_value='',
+ description='The absolute file path to the ONNX file'
+ ),
+ 'engine_file_path': DeclareLaunchArgument(
+ 'engine_file_path',
+ default_value='',
+ description='The absolute file path to the TensorRT engine file'
+ ),
+ 'input_tensor_names': DeclareLaunchArgument(
+ 'input_tensor_names',
+ default_value='["input_tensor"]',
+ description='A list of tensor names to bound to the specified input binding names'
+ ),
+ 'input_binding_names': DeclareLaunchArgument(
+ 'input_binding_names',
+ default_value='["images"]',
+ description='A list of input tensor binding names (specified by model)'
+ ),
+ 'output_tensor_names': DeclareLaunchArgument(
+ 'output_tensor_names',
+ default_value='["output_tensor"]',
+ description='A list of tensor names to bound to the specified output binding names'
+ ),
+ 'output_binding_names': DeclareLaunchArgument(
+ 'output_binding_names',
+ default_value='["output0"]',
+ description='A list of output tensor binding names (specified by model)'
+ ),
+ 'verbose': DeclareLaunchArgument(
+ 'verbose',
+ default_value='False',
+ description='Whether TensorRT should verbosely log or not'
+ ),
+ 'force_engine_update': DeclareLaunchArgument(
+ 'force_engine_update',
+ default_value='False',
+ description='Whether TensorRT should update the TensorRT engine file or not'
+ ),
+ 'confidence_threshold': DeclareLaunchArgument(
+ 'confidence_threshold',
+ default_value='0.25',
+ description='Confidence threshold to filter candidate detections during NMS'
+ ),
+ 'nms_threshold': DeclareLaunchArgument(
+ 'nms_threshold',
+ default_value='0.45',
+ description='NMS IOU threshold'
+ ),
+ 'yolov8_encoder_launch': IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': str(interface_specs['camera_resolution']['width']),
+ 'input_image_height': str(interface_specs['camera_resolution']['height']),
+ 'network_image_width': network_image_width,
+ 'network_image_height': network_image_height,
+ 'image_mean': image_mean,
+ 'image_stddev': image_stddev,
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': '/isaac_ros_examples/container',
+ 'dnn_image_encoder_namespace': 'yolov8_encoder',
+ 'image_input_topic': '/image_rect',
+ 'camera_info_input_topic': '/camera_info_rect',
+ 'tensor_output_topic': '/tensor_pub',
+ }.items(),
+ ),
+ }
+
+
+def generate_launch_description():
+ yolov8_container = ComposableNodeContainer(
+ package='rclcpp_components',
+ name='yolov8_container',
+ namespace='',
+ executable='component_container_mt',
+ composable_node_descriptions=IsaacROSYolov8LaunchFragment
+ .get_composable_nodes().values(),
+ arguments=['--ros-args', '--log-level', 'INFO'],
+ output='screen'
+ )
+
+ return launch.LaunchDescription(
+ [yolov8_container] + IsaacROSYolov8LaunchFragment.get_launch_actions().values())
diff --git a/isaac_ros_yolov8/launch/isaac_ros_yolov8_isaac_sim.launch.py b/isaac_ros_yolov8/launch/isaac_ros_yolov8_isaac_sim.launch.py
new file mode 100644
index 0000000..17bd1be
--- /dev/null
+++ b/isaac_ros_yolov8/launch/isaac_ros_yolov8_isaac_sim.launch.py
@@ -0,0 +1,213 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2024 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
+
+from ament_index_python.packages import get_package_share_directory
+import launch
+from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import ComposableNodeContainer, Node
+from launch_ros.descriptions import ComposableNode
+
+
+def generate_launch_description():
+ """Launch the DNN Image encoder, TensorRT node and YOLOv8 decoder node."""
+ launch_args = [
+ DeclareLaunchArgument(
+ 'input_image_width',
+ default_value='1920',
+ description='The input image width'),
+ DeclareLaunchArgument(
+ 'input_image_height',
+ default_value='1200',
+ description='The input image height'),
+ DeclareLaunchArgument(
+ 'network_image_width',
+ default_value='640',
+ description='The input image width that the network expects'),
+ DeclareLaunchArgument(
+ 'network_image_height',
+ default_value='640',
+ description='The input image height that the network expects'),
+ DeclareLaunchArgument(
+ 'image_mean',
+ default_value='[0.0, 0.0, 0.0]',
+ description='The mean for image normalization'),
+ DeclareLaunchArgument(
+ 'image_stddev',
+ default_value='[1.0, 1.0, 1.0]',
+ description='The standard deviation for image normalization'),
+ DeclareLaunchArgument(
+ 'model_file_path',
+ default_value='',
+ description='The absolute file path to the ONNX file'),
+ DeclareLaunchArgument(
+ 'engine_file_path',
+ default_value='',
+ description='The absolute file path to the TensorRT engine file'),
+ DeclareLaunchArgument(
+ 'input_tensor_names',
+ default_value='["input_tensor"]',
+ description='A list of tensor names to bound to the specified input binding names'),
+ DeclareLaunchArgument(
+ 'input_binding_names',
+ default_value='["images"]',
+ description='A list of input tensor binding names (specified by model)'),
+ DeclareLaunchArgument(
+ 'output_tensor_names',
+ default_value='["output_tensor"]',
+ description='A list of tensor names to bound to the specified output binding names'),
+ DeclareLaunchArgument(
+ 'output_binding_names',
+ default_value='["output0"]',
+ description='A list of output tensor binding names (specified by model)'),
+ DeclareLaunchArgument(
+ 'verbose',
+ default_value='False',
+ description='Whether TensorRT should verbosely log or not'),
+ DeclareLaunchArgument(
+ 'force_engine_update',
+ default_value='False',
+ description='Whether TensorRT should update the TensorRT engine file or not'),
+ DeclareLaunchArgument(
+ 'confidence_threshold',
+ default_value='0.25',
+ description='Confidence threshold to filter candidate detections during NMS'),
+ DeclareLaunchArgument(
+ 'nms_threshold',
+ default_value='0.45',
+ description='NMS IOU threshold'),
+ ]
+
+ # DNN Image Encoder parameters
+ input_image_width = LaunchConfiguration('input_image_width')
+ input_image_height = LaunchConfiguration('input_image_height')
+ network_image_width = LaunchConfiguration('network_image_width')
+ network_image_height = LaunchConfiguration('network_image_height')
+ image_mean = LaunchConfiguration('image_mean')
+ image_stddev = LaunchConfiguration('image_stddev')
+
+ # TensorRT parameters
+ model_file_path = LaunchConfiguration('model_file_path')
+ engine_file_path = LaunchConfiguration('engine_file_path')
+ input_tensor_names = LaunchConfiguration('input_tensor_names')
+ input_binding_names = LaunchConfiguration('input_binding_names')
+ output_tensor_names = LaunchConfiguration('output_tensor_names')
+ output_binding_names = LaunchConfiguration('output_binding_names')
+ verbose = LaunchConfiguration('verbose')
+ force_engine_update = LaunchConfiguration('force_engine_update')
+
+ # YOLOv8 Decoder parameters
+ confidence_threshold = LaunchConfiguration('confidence_threshold')
+ nms_threshold = LaunchConfiguration('nms_threshold')
+
+ image_resize_node_left = ComposableNode(
+ package='isaac_ros_image_proc',
+ plugin='nvidia::isaac_ros::image_proc::ResizeNode',
+ name='image_resize_node_left',
+ parameters=[{
+ 'output_width': network_image_width,
+ 'output_height': network_image_height,
+ 'encoding_desired': 'rgb8',
+ }],
+ remappings=[
+ ('camera_info', 'front_stereo_camera/left_rgb/camerainfo'),
+ ('image', 'front_stereo_camera/left_rgb/image_raw'),
+ ('resize/camera_info', 'front_stereo_camera/left_rgb/camerainfo_resize'),
+ ('resize/image', 'front_stereo_camera/left_rgb/image_resize')]
+ )
+
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ yolov8_encoder_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
+ 'input_image_width': input_image_width,
+ 'input_image_height': input_image_height,
+ 'network_image_width': network_image_width,
+ 'network_image_height': network_image_height,
+ 'image_mean': image_mean,
+ 'image_stddev': image_stddev,
+ 'enable_padding': 'False',
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': 'yolov8_container',
+ 'dnn_image_encoder_namespace': 'yolov8_encoder',
+ 'image_input_topic': '/front_stereo_camera/left_rgb/image_resize',
+ 'camera_info_input_topic': '/front_stereo_camera/left_rgb/camerainfo_resize',
+ 'tensor_output_topic': '/tensor_pub',
+ }.items(),
+ )
+
+ tensor_rt_node = ComposableNode(
+ name='tensor_rt',
+ package='isaac_ros_tensor_rt',
+ plugin='nvidia::isaac_ros::dnn_inference::TensorRTNode',
+ parameters=[{
+ 'model_file_path': model_file_path,
+ 'engine_file_path': engine_file_path,
+ 'output_binding_names': output_binding_names,
+ 'output_tensor_names': output_tensor_names,
+ 'input_tensor_names': input_tensor_names,
+ 'input_binding_names': input_binding_names,
+ 'verbose': verbose,
+ 'force_engine_update': force_engine_update
+ }]
+ )
+
+ yolov8_decoder_node = ComposableNode(
+ name='yolov8_decoder_node',
+ package='isaac_ros_yolov8',
+ plugin='nvidia::isaac_ros::yolov8::YoloV8DecoderNode',
+ parameters=[{
+ 'confidence_threshold': confidence_threshold,
+ 'nms_threshold': nms_threshold,
+ }]
+ )
+
+ yolov8_container = ComposableNodeContainer(
+ package='rclcpp_components',
+ name='yolov8_container',
+ namespace='',
+ executable='component_container_mt',
+ composable_node_descriptions=[image_resize_node_left, tensor_rt_node, yolov8_decoder_node],
+ output='screen'
+ )
+
+ yolov8_visualizer_node = Node(
+ package='isaac_ros_yolov8',
+ executable='isaac_ros_yolov8_visualizer.py',
+ name='yolov8_visualizer',
+ remappings=[('yolov8_encoder/resize/image', 'front_stereo_camera/left_rgb/image_resize')]
+
+ )
+
+ rqt_image_view_node = Node(
+ package='rqt_image_view',
+ executable='rqt_image_view',
+ name='image_view',
+ arguments=['/yolov8_processed_image'],
+ parameters=[
+ {'my_str': 'rgb8'},
+ ]
+ )
+
+ return launch.LaunchDescription(launch_args +
+ [yolov8_container, yolov8_encoder_launch,
+ yolov8_visualizer_node, rqt_image_view_node])
diff --git a/isaac_ros_yolov8/launch/isaac_ros_yolov8_visualize.launch.py b/isaac_ros_yolov8/launch/isaac_ros_yolov8_visualize.launch.py
index 4a5419b..74908bc 100644
--- a/isaac_ros_yolov8/launch/isaac_ros_yolov8_visualize.launch.py
+++ b/isaac_ros_yolov8/launch/isaac_ros_yolov8_visualize.launch.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
diff --git a/isaac_ros_yolov8/launch/yolov8_tensor_rt.launch.py b/isaac_ros_yolov8/launch/yolov8_tensor_rt.launch.py
index b50a732..a32e3a8 100644
--- a/isaac_ros_yolov8/launch/yolov8_tensor_rt.launch.py
+++ b/isaac_ros_yolov8/launch/yolov8_tensor_rt.launch.py
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
@@ -15,8 +15,12 @@
#
# SPDX-License-Identifier: Apache-2.0
+import os
+
+from ament_index_python.packages import get_package_share_directory
import launch
-from launch.actions import DeclareLaunchArgument
+from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
@@ -82,19 +86,25 @@ def generate_launch_description():
confidence_threshold = LaunchConfiguration('confidence_threshold')
nms_threshold = LaunchConfiguration('nms_threshold')
- encoder_node = ComposableNode(
- name='dnn_image_encoder',
- package='isaac_ros_dnn_image_encoder',
- plugin='nvidia::isaac_ros::dnn_inference::DnnImageEncoderNode',
- remappings=[('encoded_tensor', 'tensor_pub')],
- parameters=[{
+ encoder_dir = get_package_share_directory('isaac_ros_dnn_image_encoder')
+ yolov8_encoder_launch = IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ [os.path.join(encoder_dir, 'launch', 'dnn_image_encoder.launch.py')]
+ ),
+ launch_arguments={
'input_image_width': input_image_width,
'input_image_height': input_image_height,
'network_image_width': network_image_width,
'network_image_height': network_image_height,
'image_mean': image_mean,
'image_stddev': image_stddev,
- }]
+ 'attach_to_shared_component_container': 'True',
+ 'component_container_name': 'tensor_rt_container',
+ 'dnn_image_encoder_namespace': 'yolov8_encoder',
+ 'image_input_topic': '/image',
+ 'camera_info_input_topic': '/camera_info',
+ 'tensor_output_topic': '/tensor_pub',
+ }.items(),
)
tensor_rt_node = ComposableNode(
@@ -127,11 +137,11 @@ def generate_launch_description():
name='tensor_rt_container',
package='rclcpp_components',
executable='component_container_mt',
- composable_node_descriptions=[encoder_node, tensor_rt_node, yolov8_decoder_node],
+ composable_node_descriptions=[tensor_rt_node, yolov8_decoder_node],
output='screen',
arguments=['--ros-args', '--log-level', 'INFO'],
namespace=''
)
- final_launch_description = launch_args + [tensor_rt_container]
+ final_launch_description = launch_args + [tensor_rt_container, yolov8_encoder_launch]
return launch.LaunchDescription(final_launch_description)
diff --git a/isaac_ros_yolov8/launch_commands.md b/isaac_ros_yolov8/launch_commands.md
deleted file mode 100644
index f9eaddf..0000000
--- a/isaac_ros_yolov8/launch_commands.md
+++ /dev/null
@@ -1,27 +0,0 @@
-# Custom Nitros YOLOv8
-
-This sample shows how to use your custom model decoder with Isaac ROS Managed Nitros. We consider the task of Object Detection using YOLOv8 with [Isaac ROS DNN Inference](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_dnn_inference).
-
-### Launch the image publisher in Terminal 1:
-```
-ros2 run image_publisher image_publisher_node --ros-args --remap /image_raw:=/image`
-```
-
-For example (sample image people_cycles.jpg provided in this repo):
-```
-ros2 run image_publisher image_publisher_node people_cycles.jpg --ros-args --remap /image_raw:=/image
-```
-
-### Launch the inference graph in Terminal 2:
-```
-ros2 launch isaac_ros_yolov8 yolov8_tensor_rt.launch.py engine_file_path:=yolov8s_fp16.plan input_binding_names:=['images'] output_binding_names:=['output0'] network_image_width:=640 network_image_height:=640 model_file_path:=yolov8s_fp16.onnx force_engine_update:=False image_mean:=[0.485,0.456,0.406] image_stddev:=[0.229,0.224,0.225] input_image_width:=640 input_image_height:=640
-```
-
-Results will be published to `/detections_output` as Detection2DArray messages.
-
-## Visualizing results:
-```
-ros2 launch isaac_ros_yolov8 isaac_ros_yolov8_visualize.launch.py engine_file_path:=yolov8s_fp16.plan input_binding_names:=['images'] output_binding_names:=['output0'] network_image_width:=640 network_image_height:=640 model_file_path:=yolov8s_fp16.onnx force_engine_update:=False image_mean:=[0.485,0.456,0.406] image_stddev:=[0.229,0.224,0.225] input_image_width:=640 input_image_height:=640
-```
-
-An RQT image window will pop up to display resulting bounding boxes on the input image. These output images are published on the `/yolov8_processed_image` topic.
diff --git a/isaac_ros_yolov8/package.xml b/isaac_ros_yolov8/package.xml
index fb8b95e..cbc0e68 100644
--- a/isaac_ros_yolov8/package.xml
+++ b/isaac_ros_yolov8/package.xml
@@ -21,10 +21,10 @@
isaac_ros_yolov8
- 2.1.0
+ 3.0.0
Isaac ROS YOLOv8 decoding
- Hemal Shah
+ Isaac ROS Maintainers
Apache-2.0
https://developer.nvidia.com/isaac-ros-gems/
Asawaree Bhide
@@ -45,6 +45,7 @@
isaac_ros_managed_nitros
isaac_ros_nitros_interfaces
isaac_ros_tensor_list_interfaces
+ isaac_ros_nitros_tensor_list_type
python3-opencv
libopencv-dev
cv_bridge
@@ -55,6 +56,9 @@
ament_lint_common
isaac_ros_test
+ isaac_ros_tensor_rt
+ isaac_ros_dnn_image_encoder
+
ament_cmake
diff --git a/isaac_ros_yolov8/scripts/isaac_ros_yolov8_visualizer.py b/isaac_ros_yolov8/scripts/isaac_ros_yolov8_visualizer.py
index 45463d5..41f24ac 100755
--- a/isaac_ros_yolov8/scripts/isaac_ros_yolov8_visualizer.py
+++ b/isaac_ros_yolov8/scripts/isaac_ros_yolov8_visualizer.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2023-2024 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.
@@ -131,7 +131,7 @@ def __init__(self):
self._image_subscription = message_filters.Subscriber(
self,
Image,
- 'image')
+ '/yolov8_encoder/resize/image')
self.time_synchronizer = message_filters.TimeSynchronizer(
[self._detections_subscription, self._image_subscription],
diff --git a/isaac_ros_yolov8/src/yolov8_decoder_node.cpp b/isaac_ros_yolov8/src/yolov8_decoder_node.cpp
index 5fd4bfe..b01f71c 100644
--- a/isaac_ros_yolov8/src/yolov8_decoder_node.cpp
+++ b/isaac_ros_yolov8/src/yolov8_decoder_node.cpp
@@ -1,5 +1,5 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+// Copyright (c) 2023-2024 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.
diff --git a/resources/people_cycles.jpg b/resources/people_cycles.jpg
deleted file mode 100644
index ae3a584..0000000
--- a/resources/people_cycles.jpg
+++ /dev/null
@@ -1,3 +0,0 @@
-version https://git-lfs.github.com/spec/v1
-oid sha256:a2d384fea3638b9c6726255f599148c78f95dc2f788e29e12619d455ee0fe535
-size 78412
diff --git a/resources/yolov8s_fp16.onnx b/resources/yolov8s_fp16.onnx
deleted file mode 100644
index 4f9c451..0000000
--- a/resources/yolov8s_fp16.onnx
+++ /dev/null
@@ -1,3 +0,0 @@
-version https://git-lfs.github.com/spec/v1
-oid sha256:8ab61094d96925b1d8318e179c038772df71be0416a49651148989f862880154
-size 44824535