Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
61 changes: 61 additions & 0 deletions isaac_ros_rtdetr/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0

cmake_minimum_required(VERSION 3.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)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(vision_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})

ament_auto_find_build_dependencies()
find_package(ament_cmake_python REQUIRED)

# rtdetr Decoder node
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;$<TARGET_FILE:rtdetr_decoder_node>\n")

target_link_libraries(rtdetr_decoder_node ${OpenCV_LIBRARIES})

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)
endif()

# Visualizer python scripts



ament_auto_package(INSTALL_TO_SHARE launch)
69 changes: 69 additions & 0 deletions isaac_ros_rtdetr/include/isaac_ros_rtdetr/rtdetr_decoder_node.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
// Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// SPDX-License-Identifier: Apache-2.0

#ifndef ISAAC_ROS_YOLOV8__YOLOV8_DECODER_NODE_HPP_
#define ISAAC_ROS_YOLOV8__YOLOV8_DECODER_NODE_HPP_

#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"

#include "isaac_ros_managed_nitros/managed_nitros_subscriber.hpp"

#include "std_msgs/msg/string.hpp"
#include "vision_msgs/msg/detection2_d_array.hpp"
#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.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<nvidia::isaac_ros::nitros::ManagedNitrosSubscriber<
nvidia::isaac_ros::nitros::NitrosTensorListView>> nitros_sub_;

// Publisher for output Detection2DArray messages
rclcpp::Publisher<vision_msgs::msg::Detection2DArray>::SharedPtr pub_;

// Name of tensor in NitrosTensorList
std::string tensor_conf_name_{};
std::string tensor_bboxes_name_{};
std::string tensor_labels_name_{};

double confidence_threshold_;

};

} // namespace rtdetr
} // namespace isaac_ros
} // namespace nvidia

#endif // ISAAC_ROS_YOLOV8__YOLOV8_DECODER_NODE_HPP_
16 changes: 16 additions & 0 deletions isaac_ros_rtdetr/isaac_ros_yolonas/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0
46 changes: 46 additions & 0 deletions isaac_ros_rtdetr/launch/isaac_ros_yolov8_visualize.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0

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 Node


def generate_launch_description():
my_package_dir = get_package_share_directory('isaac_ros_rtdetr')
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
my_package_dir, 'launch'),
'/rtdetr_tensor_rt.launch.py'])
),
Node(
package='isaac_ros_rtdetr',
executable='isaac_ros_rtdetr_visualizer.py',
name='rtdetr_visualizer'
),
Node(
package='rqt_image_view',
executable='rqt_image_view',
name='image_view',
arguments=['/rtdetr_processed_image']
)
])
137 changes: 137 additions & 0 deletions isaac_ros_rtdetr/launch/yolov8_tensor_rt.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,137 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0

import launch
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
"""Generate launch description for TensorRT ROS 2 node."""
# By default loads and runs mobilenetv2-1.0 included in isaac_ros_dnn_inference/models
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_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='[""]',
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='[""]',
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'),
]

# 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')

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=[{
'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,
}]
)

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_node',
package='isaac_ros_rtdetr',
plugin='nvidia::isaac_ros::rtdetr::RTDETRDecoderNode',
parameters=[{
'confidence_threshold': confidence_threshold,
'nms_threshold': nms_threshold,
}]
)

tensor_rt_container = ComposableNodeContainer(
name='tensor_rt_container',
package='rclcpp_components',
executable='component_container_mt',
composable_node_descriptions=[encoder_node, tensor_rt_node, rtdetr_decoder_node],
output='screen',
arguments=['--ros-args', '--log-level', 'INFO'],
namespace=''
)

final_launch_description = launch_args + [tensor_rt_container]
return launch.LaunchDescription(final_launch_description)
27 changes: 27 additions & 0 deletions isaac_ros_rtdetr/launch_commands.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# 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 <path-to-image> --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_rtdetr rtdetr_tensor_rt.launch.py engine_file_path:=rtdetrs_fp16.plan input_binding_names:=['images'] output_binding_names:=['output0'] network_image_width:=640 network_image_height:=640 model_file_path:=rtdetrs_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_rtdetr isaac_ros_rtdetr_visualize.launch.py engine_file_path:=rtdetrs_fp16.plan input_binding_names:=['images'] output_binding_names:=['output0'] network_image_width:=640 network_image_height:=640 model_file_path:=rtdetrs_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 `/rtdetr_processed_image` topic.
Loading