├── .gitattributes
├── .gitignore
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── gxf_isaac_bi3d
├── CMakeLists.txt
├── gxf
│ ├── extensions
│ │ └── bi3d
│ │ │ ├── bi3d.cpp
│ │ │ ├── components
│ │ │ ├── bi3d_depthview.cpp
│ │ │ ├── bi3d_depthview.hpp
│ │ │ ├── bi3d_inference.cpp
│ │ │ ├── bi3d_inference.hpp
│ │ │ ├── bi3d_postprocessor.cpp
│ │ │ ├── bi3d_postprocessor.cu
│ │ │ ├── bi3d_postprocessor.cu.hpp
│ │ │ ├── bi3d_postprocessor.hpp
│ │ │ └── bi3d_postprocessor_utils.hpp
│ │ │ └── inference
│ │ │ ├── Bi3D.cpp
│ │ │ ├── Bi3D.h
│ │ │ ├── Bi3DPostProcessor.cpp
│ │ │ ├── Bi3DPreProcessor.cpp
│ │ │ ├── Bi3D_detail.cpp
│ │ │ ├── Bi3D_detail.hpp
│ │ │ └── Model.h
│ └── gems
│ │ ├── dnn_inferencer
│ │ └── inferencer
│ │ │ ├── Errors.cpp
│ │ │ ├── Errors.h
│ │ │ ├── IInferenceBackend.h
│ │ │ ├── Inferencer.cpp
│ │ │ ├── Inferencer.h
│ │ │ ├── TensorRTInferencer.cpp
│ │ │ ├── TensorRTInferencer.h
│ │ │ ├── TensorRTUtils.cpp
│ │ │ ├── TensorRTUtils.h
│ │ │ ├── TritonGrpcInferencer.cpp
│ │ │ ├── TritonGrpcInferencer.h
│ │ │ ├── TritonUtils.cpp
│ │ │ └── TritonUtils.h
│ │ └── hash
│ │ ├── hash_file.cpp
│ │ ├── hash_file.hpp
│ │ ├── sha256.cpp
│ │ └── sha256.hpp
└── package.xml
├── isaac_ros_bi3d
├── CMakeLists.txt
├── config
│ ├── bi3d_node.yaml
│ ├── isaac_ros_bi3d_isaac_sim.rviz
│ ├── isaac_ros_bi3d_zed.rviz
│ ├── realsense.yaml
│ └── zed.yaml
├── include
│ └── isaac_ros_bi3d
│ │ └── bi3d_node.hpp
├── isaac_ros_bi3d
│ └── __init__.py
├── launch
│ ├── isaac_ros_bi3d.launch.py
│ ├── isaac_ros_bi3d_core.launch.py
│ ├── isaac_ros_bi3d_hawk.launch.py
│ ├── isaac_ros_bi3d_isaac_sim.launch.py
│ └── isaac_ros_bi3d_realsense.launch.py
├── package.xml
├── scripts
│ └── isaac_ros_bi3d_visualizer.py
├── src
│ └── bi3d_node.cpp
└── test
│ ├── bi3d_node_test.cpp
│ ├── camera_info.json
│ ├── dummy_featnet_model.onnx
│ ├── dummy_segnet_model.onnx
│ └── isaac_ros_bi3d_test.py
└── isaac_ros_nitros_bi3d_inference_param_array_type
├── CMakeLists.txt
├── include
└── isaac_ros_nitros_bi3d_inference_param_array_type
│ └── nitros_bi3d_inference_param_array.hpp
├── package.xml
├── src
└── nitros_bi3d_inference_param_array.cpp
└── test
├── config
└── test_forward_node.yaml
├── isaac_ros_nitros_bi3d_inference_param_array_type_test_pol.py
└── src
└── nitros_bi3d_inference_param_array_forward_node.cpp
/.gitattributes:
--------------------------------------------------------------------------------
1 | # Ignore Python files in linguist
2 | *.py linguist-detectable=false
3 |
4 | # Images
5 | *.gif filter=lfs diff=lfs merge=lfs -text
6 | *.jpg filter=lfs diff=lfs merge=lfs -text
7 | *.png filter=lfs diff=lfs merge=lfs -text
8 | *.psd filter=lfs diff=lfs merge=lfs -text
9 |
10 | # Archives
11 | *.gz filter=lfs diff=lfs merge=lfs -text
12 | *.tar filter=lfs diff=lfs merge=lfs -text
13 | *.zip filter=lfs diff=lfs merge=lfs -text
14 |
15 | # Documents
16 | *.pdf filter=lfs diff=lfs merge=lfs -text
17 |
18 | # Shared libraries
19 | *.so filter=lfs diff=lfs merge=lfs -text
20 | *.so.* filter=lfs diff=lfs merge=lfs -text
21 |
22 | # ROS Bags
23 | **/resources/**/*.db3 filter=lfs diff=lfs merge=lfs -text
24 | **/resources/**/*.yaml filter=lfs diff=lfs merge=lfs -text
25 |
26 | # DNN Model files
27 | *.onnx filter=lfs diff=lfs merge=lfs -text
28 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # Ignore all pycache files
2 | **/__pycache__/**
3 |
4 | # Ignore TensorRT plan files
5 | *.plan
6 | *.engine
7 |
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | # Isaac ROS Contribution Rules
2 |
3 | Any contribution that you make to this repository will
4 | be under the Apache 2 License, as dictated by that
5 | [license](http://www.apache.org/licenses/LICENSE-2.0.html):
6 |
7 | > **5. Submission of Contributions.** Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions.
8 |
9 | Contributors must sign-off each commit by adding a `Signed-off-by: ...`
10 | line to commit messages to certify that they have the right to submit
11 | the code they are contributing to the project according to the
12 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/).
13 |
14 | [//]: # (202201002)
15 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Isaac ROS Depth Segmentation
2 |
3 | NVIDIA-accelerated packages for depth segmentation.
4 |
5 |

6 |
7 | ---
8 |
9 | ## Webinar Available
10 |
11 | Learn how to use this package by watching our on-demand webinar: [Using ML Models in ROS 2 to Robustly Estimate Distance to Obstacles](https://gateway.on24.com/wcc/experience/elitenvidiabrill/1407606/3998202/isaac-ros-webinar-series)
12 |
13 | ---
14 |
15 | ### Overview
16 |
17 | Isaac ROS Depth Segmentation provides NVIDIA NVIDIA-accelerated packages for
18 | depth segmentation. The `isaac_ros_bi3d` package uses the
19 | optimized [Bi3D DNN
20 | model](https://catalog.ngc.nvidia.com/orgs/nvidia/teams/isaac/models/bi3d_proximity_segmentation)
21 | to perform stereo-depth estimation via binary classification, which is
22 | used for depth segmentation. Depth segmentation can be used to
23 | determine whether an obstacle is within a proximity field and to avoid
24 | collisions with obstacles during navigation.
25 |
26 | 
27 |
28 | [Bi3D](https://arxiv.org/abs/2005.07274) is used in a graph of nodes
29 | to provide depth segmentation from a time-synchronized input left
30 | and right stereo image pair. Images to Bi3D need to be rectified and
31 | resized to the appropriate input resolution. The aspect ratio of the
32 | image needs to be maintained; hence, a crop and resize may be required
33 | to maintain the input aspect ratio. The graph for DNN encode, to DNN
34 | inference, to DNN decode is part of the Bi3D node. Inference is
35 | performed using TensorRT, as the Bi3D DNN model is designed to use
36 | optimizations supported by TensorRT.
37 |
38 | Compared to other stereo disparity functions, depth segmentation
39 | provides a prediction of whether an obstacle is within a proximity
40 | field, as opposed to continuous depth, while simultaneously predicting
41 | freespace from the ground plane, which other functions typically do not
42 | provide. Also unlike other stereo disparity functions in Isaac ROS,
43 | depth segmentation runs on NVIDIA DLA (deep learning accelerator),
44 | which is separate and independent from the GPU. For more information on
45 | disparity, refer to [this
46 | page](https://en.wikipedia.org/wiki/Binocular_disparity).
47 |
48 | > [!Note]
49 | > This DNN is optimized for and evaluated with RGB global shutter camera images,
50 | > and accuracy may vary on monochrome images.
51 |
52 | ### Isaac ROS NITROS Acceleration
53 |
54 | This package is powered by [NVIDIA Isaac Transport for ROS (NITROS)](https://developer.nvidia.com/blog/improve-perception-performance-for-ros-2-applications-with-nvidia-isaac-transport-for-ros/), which leverages type adaptation and negotiation to optimize message formats and dramatically accelerate communication between participating nodes.
55 |
56 | ### Performance
57 |
58 | | Sample Graph
| Input Size
| AGX Orin
| Orin NX
| x86_64 w/ RTX 4090
|
59 | |-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|--------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------|
60 | | [Depth Segmentation Node](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/benchmarks/isaac_ros_bi3d_benchmark/scripts/isaac_ros_bi3d_node.py)
| 576p
| [41.4 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-agx_orin.json)
80 ms @ 30Hz
| [28.1 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-orin_nx.json)
98 ms @ 30Hz
| [105 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-x86-4090.json)
25 ms @ 30Hz
|
61 |
62 | ---
63 |
64 | ### Documentation
65 |
66 | Please visit the [Isaac ROS Documentation](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/index.html) to learn how to use this repository.
67 |
68 | ---
69 |
70 | ### Packages
71 |
72 | * [`isaac_ros_bi3d`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html)
73 | * [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html#quickstart)
74 | * [Try More Examples](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html#try-more-examples)
75 | * [Model Preparation](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html#model-preparation)
76 | * [Troubleshooting](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html#troubleshooting)
77 | * [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_depth_segmentation/isaac_ros_bi3d/index.html#api)
78 |
79 | ### Latest
80 |
81 | Update 2024-12-10: Update to be compatible with JetPack 6.1
82 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | # SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | # Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | #
4 | # Licensed under the Apache License, Version 2.0 (the "License");
5 | # you may not use this file except in compliance with the License.
6 | # You may obtain a copy of the License at
7 | #
8 | # http://www.apache.org/licenses/LICENSE-2.0
9 | #
10 | # Unless required by applicable law or agreed to in writing, software
11 | # distributed under the License is distributed on an "AS IS" BASIS,
12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | # See the License for the specific language governing permissions and
14 | # limitations under the License.
15 | #
16 | # SPDX-License-Identifier: Apache-2.0
17 |
18 | cmake_minimum_required(VERSION 3.22.1)
19 | project(gxf_isaac_bi3d LANGUAGES C CXX)
20 |
21 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
22 | add_compile_options(-fPIC -w)
23 | endif()
24 |
25 | find_package(ament_cmake_auto REQUIRED)
26 | ament_auto_find_build_dependencies()
27 |
28 | enable_language(CUDA)
29 |
30 | # Dependencies
31 | find_package(CUDAToolkit)
32 | find_package(yaml-cpp)
33 | find_package(TENSORRT)
34 | find_package(Eigen3)
35 |
36 | # Bi3D extension
37 | ament_auto_add_library(${PROJECT_NAME} SHARED
38 | gxf/extensions/bi3d/bi3d.cpp
39 | gxf/extensions/bi3d/components/bi3d_postprocessor.cpp
40 | gxf/extensions/bi3d/components/bi3d_inference.cpp
41 | gxf/extensions/bi3d/components/bi3d_postprocessor.cu
42 | gxf/extensions/bi3d/components/bi3d_depthview.cpp
43 |
44 | gxf/extensions/bi3d/inference/Bi3D_detail.cpp
45 | gxf/extensions/bi3d/inference/Bi3D_detail.hpp
46 | gxf/extensions/bi3d/inference/Bi3D.cpp
47 | gxf/extensions/bi3d/inference/Bi3D.h
48 | gxf/extensions/bi3d/inference/Bi3DPreProcessor.cpp
49 | gxf/extensions/bi3d/inference/Bi3DPostProcessor.cpp
50 |
51 | # Inferencer (Bi3D only)
52 | gxf/gems/dnn_inferencer/inferencer/TensorRTInferencer.cpp
53 | gxf/gems/dnn_inferencer/inferencer/TensorRTUtils.cpp
54 | gxf/gems/dnn_inferencer/inferencer/Inferencer.cpp
55 | gxf/gems/dnn_inferencer/inferencer/Errors.cpp
56 | )
57 |
58 | target_include_directories(${PROJECT_NAME} PRIVATE "${CMAKE_CURRENT_SOURCE_DIR}/gxf")
59 |
60 | target_link_libraries(${PROJECT_NAME}
61 | Eigen3::Eigen
62 | CUDA::cudart
63 | CUDA::nppc
64 | CUDA::nppial
65 | CUDA::nppicc
66 | CUDA::nppidei
67 | CUDA::nppif
68 | CUDA::nppig
69 | CUDA::nppisu
70 | CUDA::nppitc
71 | TENSORRT::nvinfer
72 | yaml-cpp
73 | )
74 |
75 | set_target_properties(${PROJECT_NAME} PROPERTIES
76 | BUILD_WITH_INSTALL_RPATH TRUE
77 | BUILD_RPATH_USE_ORIGIN TRUE
78 | INSTALL_RPATH_USE_LINK_PATH TRUE
79 | )
80 |
81 | # Install the binary file
82 | install(TARGETS ${PROJECT_NAME} DESTINATION share/${PROJECT_NAME}/gxf/lib)
83 |
84 |
85 | # Embed versioning information into installed files
86 | ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common)
87 | include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake")
88 | generate_version_info(${PROJECT_NAME})
89 |
90 | ament_auto_package(INSTALL_TO_SHARE)
91 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/bi3d.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #include "extensions/bi3d/components/bi3d_depthview.hpp"
18 | #include "extensions/bi3d/components/bi3d_inference.hpp"
19 | #include "extensions/bi3d/components/bi3d_postprocessor.hpp"
20 | #include "gxf/std/extension_factory_helper.hpp"
21 |
22 | GXF_EXT_FACTORY_BEGIN()
23 |
24 | GXF_EXT_FACTORY_SET_INFO(0xce7c6985267a4ec7, 0xa073030e16e49f29, "Bi3D",
25 | "Extension containing Bi3D related components",
26 | "Isaac SDK", "2.0.0", "LICENSE");
27 |
28 | GXF_EXT_FACTORY_ADD(0x9cfc86f71c7c4102, 0xade57d2d4faf6453,
29 | nvidia::isaac::bi3d::DepthView, nvidia::gxf::Codelet,
30 | "Bi3d depth map generator");
31 |
32 | GXF_EXT_FACTORY_ADD(0x2eb361c045894aec, 0x831550ff5f177d87,
33 | nvidia::isaac::bi3d::Bi3DPostprocessor, nvidia::gxf::Codelet,
34 | "Bi3D post processor");
35 |
36 | GXF_EXT_FACTORY_ADD(0xdcba0cf83a5340d2, 0x8404788350ad2324,
37 | nvidia::isaac::Bi3DInference, nvidia::gxf::Codelet,
38 | "Bi3D Inference");
39 |
40 | GXF_EXT_FACTORY_END()
41 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_depthview.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #include "extensions/bi3d/components/bi3d_depthview.hpp"
18 |
19 | #include
20 | #include
21 | #include
22 |
23 | #include "gems/core/image/image.hpp"
24 | #include "gems/core/tensor/tensor.hpp"
25 | #include "gems/image/io.hpp"
26 | #include "gems/image/utils.hpp"
27 | #include "gxf/multimedia/video.hpp"
28 |
29 | namespace nvidia {
30 | namespace isaac {
31 | namespace bi3d {
32 |
33 | // Indicates Depth View Color Scheme.
34 | enum DepthViewColorScheme {
35 | DepthViewColorScheme_ErrorColor = 1,
36 | DepthViewColorScheme_RedGreenBlack,
37 | DepthViewColorScheme_DistanceMap,
38 | DepthViewColorScheme_StarryNight,
39 | DepthViewColorScheme_BlackAndWhite
40 | };
41 |
42 | gxf_result_t DepthView::registerInterface(gxf::Registrar* registrar) {
43 | gxf::Expected result;
44 | result &= registrar->parameter(
45 | data_receiver_, "data_receiver",
46 | "Receiver to get the data", "");
47 | result &= registrar->parameter(
48 | output_tensor_, "output_tensor",
49 | "The name of the tensor to be transmitted", "");
50 | result &= registrar->parameter(
51 | output_as_tensor_, "output_as_tensor",
52 | "The flag to indicate that output is a tensor or video buffer", "", true);
53 | result &= registrar->parameter(data_transmitter_, "data_transmitter",
54 | "Transmitter to send the data", "");
55 | result &= registrar->parameter(
56 | allocator_, "allocator",
57 | "Memory pool for allocating output data", "");
58 | result &= registrar->parameter(
59 | color_scheme_, "color_scheme",
60 | "The color scheme for Bi3d depth",
61 | "Following are supported color schemes: "
62 | "1 - ErrorColor"
63 | "2 - RedGreenBlack"
64 | "3 - DistanceMap"
65 | "4 - StarryNight"
66 | "5 - BlackAndWhite",
67 | 5);
68 | result &= registrar->parameter(
69 | min_disparity_, "min_disparity",
70 | "Minimum disparity used for colorization", "0.0f");
71 | result &= registrar->parameter(
72 | max_disparity_, "max_disparity",
73 | "Maximum disparity used for colorization", "255.0f");
74 | return gxf::ToResultCode(result);
75 | }
76 |
77 | gxf_result_t DepthView::start() {
78 | switch (color_scheme_) {
79 | case DepthViewColorScheme_ErrorColor:
80 | gradient_ = ::nvidia::isaac::ErrorColorGradient();
81 | break;
82 |
83 | case DepthViewColorScheme_RedGreenBlack:
84 | gradient_ = ::nvidia::isaac::ColorGradient({
85 | ::nvidia::isaac::Pixel3ub{0, 0, 0}, ::nvidia::isaac::Pixel3ub{118, 185, 0},
86 | ::nvidia::isaac::Pixel3ub{221, 86, 47}, ::nvidia::isaac::Pixel3ub{255, 0, 0}});
87 | break;
88 |
89 | case DepthViewColorScheme_DistanceMap:
90 | gradient_ = ::nvidia::isaac::DistanceColorGradient();
91 | break;
92 |
93 | case DepthViewColorScheme_StarryNight:
94 | gradient_ = ::nvidia::isaac::StarryNightColorGradient();
95 | break;
96 |
97 | case DepthViewColorScheme_BlackAndWhite:
98 | gradient_ = ::nvidia::isaac::BlackWhiteColorGradient();
99 | break;
100 |
101 | default:
102 | gradient_ = ::nvidia::isaac::BlackWhiteColorGradient();
103 | break;
104 | }
105 | return GXF_SUCCESS;
106 | }
107 |
108 | gxf_result_t DepthView::tick() {
109 | auto entity = data_receiver_->receive();
110 | if (!entity) {
111 | return gxf::ToResultCode(entity);
112 | }
113 |
114 | // Get input
115 | auto input_frame = entity.value().get();
116 | if (!input_frame) {
117 | GXF_LOG_ERROR("Failed to get input frame from message");
118 | return gxf::ToResultCode(input_frame);
119 | }
120 |
121 | if (input_frame.value()->video_frame_info().color_format !=
122 | gxf::VideoFormat::GXF_VIDEO_FORMAT_D32F) {
123 | GXF_LOG_ERROR("Only supports D32F images");
124 | return GXF_FAILURE;
125 | }
126 |
127 | if (input_frame.value()->storage_type() != gxf::MemoryStorageType::kHost) {
128 | GXF_LOG_ERROR("Only supports video buffer on Host.");
129 | return GXF_FAILURE;
130 | }
131 |
132 | int inputWidth = input_frame.value()->video_frame_info().width;
133 | int inputHeight = input_frame.value()->video_frame_info().height;
134 | ::nvidia::isaac::ImageView1f input_depthview = ::nvidia::isaac::CreateImageView(
135 | reinterpret_cast(input_frame.value()->pointer()),
136 | inputHeight, inputWidth);
137 |
138 | // Create output message
139 | auto output_message = gxf::Entity::New(context());
140 | if (!output_message) {
141 | return gxf::ToResultCode(output_message);
142 | }
143 |
144 | auto output_name = output_tensor_.try_get() ? output_tensor_.try_get()->c_str() : nullptr;
145 | ::nvidia::isaac::ImageView3ub output_image;
146 |
147 | if (output_as_tensor_) {
148 | // Create tensor
149 | auto output_tensor = output_message.value().add(output_name);
150 | if (!output_tensor) {
151 | return gxf::ToResultCode(output_tensor);
152 | }
153 |
154 | const gxf::Shape shape({inputHeight, inputWidth, 3});
155 | auto result =
156 | output_tensor.value()->reshapeCustom(shape, gxf::PrimitiveType::kUnsigned8, 1,
157 | gxf::Unexpected{GXF_UNINITIALIZED_VALUE},
158 | gxf::MemoryStorageType::kHost, allocator_);
159 | if (!result) {
160 | GXF_LOG_ERROR("reshape tensor failed.");
161 | return GXF_FAILURE;
162 | }
163 |
164 | output_image = ::nvidia::isaac::CreateImageView(
165 | output_tensor.value()->data().value(),
166 | inputHeight, inputWidth);
167 | } else {
168 | // Create video buffer
169 | auto output_frame = output_message.value().add(output_name);
170 | if (!output_frame) {
171 | return gxf::ToResultCode(output_frame);
172 | }
173 |
174 | std::array planes{
175 | gxf::ColorPlane("RGB", 3, inputWidth * 3)};
176 | gxf::VideoFormatSize video_format_size;
177 | const uint64_t size = video_format_size.size(inputWidth, inputHeight, planes);
178 | const gxf::VideoBufferInfo buffer_info{static_cast(inputWidth),
179 | static_cast(inputHeight),
180 | gxf::VideoFormat::GXF_VIDEO_FORMAT_RGB,
181 | {planes.begin(), planes.end()},
182 | gxf::SurfaceLayout::GXF_SURFACE_LAYOUT_PITCH_LINEAR};
183 | output_frame.value()->resizeCustom(
184 | buffer_info, size,
185 | gxf::MemoryStorageType::kHost, allocator_);
186 | output_image = ::nvidia::isaac::CreateImageView(
187 | output_frame.value()->pointer(),
188 | inputHeight, inputWidth);
189 | }
190 |
191 | ::nvidia::isaac::Colorize(input_depthview, gradient_, min_disparity_,
192 | max_disparity_, output_image);
193 |
194 | // Send the data
195 | return gxf::ToResultCode(data_transmitter_->publish(output_message.value()));
196 | }
197 |
198 | } // namespace bi3d
199 | } // namespace isaac
200 | } // namespace nvidia
201 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_depthview.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #pragma once
18 |
19 | #include
20 | #include
21 |
22 | #include "gems/image/color.hpp"
23 | #include "gxf/std/codelet.hpp"
24 | #include "gxf/std/receiver.hpp"
25 | #include "gxf/std/tensor.hpp"
26 | #include "gxf/std/transmitter.hpp"
27 |
28 | namespace nvidia {
29 | namespace isaac {
30 | namespace bi3d {
31 |
32 | class DepthView : public gxf::Codelet {
33 | public:
34 | gxf_result_t registerInterface(gxf::Registrar* registrar) override;
35 | gxf_result_t start() override;
36 | gxf_result_t tick() override;
37 | gxf_result_t stop() override {return GXF_SUCCESS;};
38 |
39 | private:
40 | // Data receiver to get data
41 | gxf::Parameter> data_receiver_;
42 | // The name of the output tensor
43 | gxf::Parameter output_tensor_;
44 | // The flag that indicates if output as a tensor
45 | gxf::Parameter output_as_tensor_;
46 | // Data transmitter to send the data
47 | gxf::Parameter> data_transmitter_;
48 | // Allocator
49 | gxf::Parameter> allocator_;
50 | // Color scheme
51 | gxf::Parameter color_scheme_;
52 | // Minimum disparity value
53 | gxf::Parameter min_disparity_;
54 | // maximum disparity value
55 | gxf::Parameter max_disparity_;
56 |
57 | // Color gradient used to color different depths
58 | ::nvidia::isaac::ColorGradient gradient_;
59 | };
60 |
61 | } // namespace bi3d
62 | } // namespace isaac
63 | } // namespace nvidia
64 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_inference.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 | #include
23 | #include
24 | #include
25 |
26 | #include "extensions/bi3d/inference/Bi3D.h"
27 | #include "gxf/cuda/cuda_stream_pool.hpp"
28 | #include "gxf/std/allocator.hpp"
29 | #include "gxf/std/codelet.hpp"
30 | #include "gxf/std/receiver.hpp"
31 | #include "gxf/std/transmitter.hpp"
32 |
33 | namespace nvidia {
34 | namespace isaac {
35 | // CV-Core Bi3D GXF Codelet
36 | class Bi3DInference : public gxf::Codelet {
37 | public:
38 | Bi3DInference() = default;
39 | ~Bi3DInference() = default;
40 |
41 | gxf_result_t registerInterface(gxf::Registrar* registrar) override;
42 | gxf_result_t initialize() override {
43 | return GXF_SUCCESS;
44 | }
45 | gxf_result_t deinitialize() override {
46 | return GXF_SUCCESS;
47 | }
48 |
49 | gxf_result_t start() override;
50 | gxf_result_t tick() override;
51 | gxf_result_t stop() override;
52 |
53 | private:
54 | // gxf stream handling
55 | gxf::Handle cuda_stream_ = nullptr;
56 |
57 | // cvcore image pre-processing params for Bi3D
58 | cvcore::tensor_ops::ImagePreProcessingParams preProcessorParams;
59 | // cvcore model input params for Bi3D
60 | bi3d::ModelInputParams modelInputParams;
61 | // cvcore inference params for Bi3D
62 | cvcore::inferencer::TensorRTInferenceParams featureInferenceParams;
63 | cvcore::inferencer::TensorRTInferenceParams featureHRInferenceParams;
64 | cvcore::inferencer::TensorRTInferenceParams refinementInferenceParams;
65 | cvcore::inferencer::TensorRTInferenceParams segmentationInferenceParams;
66 | // extra params for Bi3D
67 | bi3d::Bi3D::Bi3DParams extraParams;
68 | // cvcore Bi3D object
69 | std::unique_ptr objBi3D;
70 | cvcore::tensor_ops::Array disparityValues;
71 |
72 | // The name of the input left image tensor
73 | gxf::Parameter left_image_name_;
74 | // The name of the input right image tensor
75 | gxf::Parameter right_image_name_;
76 | // The name of the output tensor
77 | gxf::Parameter output_name_;
78 | // Cuda Stream Pool
79 | gxf::Parameter> stream_pool_;
80 | // Data allocator to create a tensor
81 | gxf::Parameter> pool_;
82 | // Data allocator to forward the disparity array
83 | gxf::Parameter> forward_pool_;
84 | // Data receiver to get left image data
85 | gxf::Parameter> left_image_receiver_;
86 | // Data receiver to get right image data
87 | gxf::Parameter> right_image_receiver_;
88 | // Optional receiver for dynamic disparity values input
89 | gxf::Parameter> disparity_receiver_;
90 | // Data transmitter to send the data
91 | gxf::Parameter> output_transmitter_;
92 |
93 | // Pre-processing params for Bi3D
94 | gxf::Parameter image_type_;
95 | gxf::Parameter> pixel_mean_;
96 | gxf::Parameter> normalization_;
97 | gxf::Parameter> standard_deviation_;
98 |
99 | // Model input params for Bi3D
100 | gxf::Parameter max_batch_size_;
101 | gxf::Parameter input_layer_width_;
102 | gxf::Parameter input_layer_height_;
103 | gxf::Parameter model_input_type_;
104 |
105 | // Inference params for Bi3D
106 | gxf::Parameter featnet_engine_file_path_;
107 | gxf::Parameter> featnet_input_layers_name_;
108 | gxf::Parameter> featnet_output_layers_name_;
109 |
110 | gxf::Parameter featnet_hr_engine_file_path_;
111 | gxf::Parameter> featnet_hr_input_layers_name_;
112 | gxf::Parameter> featnet_hr_output_layers_name_;
113 |
114 | gxf::Parameter refinenet_engine_file_path_;
115 | gxf::Parameter> refinenet_input_layers_name_;
116 | gxf::Parameter> refinenet_output_layers_name_;
117 |
118 | gxf::Parameter segnet_engine_file_path_;
119 | gxf::Parameter> segnet_input_layers_name_;
120 | gxf::Parameter> segnet_output_layers_name_;
121 |
122 | // Extra params for Bi3D
123 | gxf::Parameter engine_type_;
124 | gxf::Parameter apply_sigmoid_;
125 | gxf::Parameter apply_thresholding_;
126 | gxf::Parameter threshold_value_low_;
127 | gxf::Parameter threshold_value_high_;
128 | gxf::Parameter threshold_;
129 | gxf::Parameter apply_edge_refinement_;
130 | gxf::Parameter max_disparity_levels_;
131 | gxf::Parameter> disparity_values_;
132 |
133 | // Decide which timestamp to pass down
134 | gxf::Parameter timestamp_policy_;
135 | };
136 |
137 | } // namespace isaac
138 | } // namespace nvidia
139 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_postprocessor.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #include "extensions/bi3d/components/bi3d_postprocessor.hpp"
18 |
19 | #include
20 |
21 | #include "extensions/bi3d/components/bi3d_postprocessor.cu.hpp"
22 | #include "gems/video_buffer/allocator.hpp"
23 | #include "gxf/core/parameter_parser_std.hpp"
24 | #include "gxf/std/timestamp.hpp"
25 |
26 | namespace nvidia {
27 | namespace isaac {
28 | namespace bi3d {
29 |
30 | gxf_result_t Bi3DPostprocessor::registerInterface(gxf::Registrar* registrar) noexcept {
31 | gxf::Expected result;
32 | result &= registrar->parameter(
33 | bi3d_receiver_, "bi3d_receiver", "Bi3D receiver",
34 | "Tensor from Bi3D");
35 | result &= registrar->parameter(
36 | output_transmitter_, "output_transmitter", "Output transmitter",
37 | "The collapsed output of Bi3D");
38 | result &= registrar->parameter(
39 | pool_, "pool", "Pool",
40 | "Allocator instance for output videobuffer");
41 | result &= registrar->parameter(
42 | disparity_values_, "disparity_values", "Disparity values"
43 | "Disparities values used for Bi3D inference");
44 | return gxf::ToResultCode(result);
45 | }
46 |
47 | gxf_result_t Bi3DPostprocessor::tick() noexcept {
48 | // Receive bi3d output
49 | auto bi3d_message = bi3d_receiver_->receive();
50 | if (!bi3d_message) {
51 | GXF_LOG_ERROR("Failed to get message");
52 | return gxf::ToResultCode(bi3d_message);
53 | }
54 |
55 | // Get Bi3D disparity tensor
56 | auto bi3d_disparity_tensor = bi3d_message->get("disparity");
57 | if (!bi3d_disparity_tensor) {
58 | GXF_LOG_ERROR("Failed to get disparity image tensor");
59 | return gxf::ToResultCode(bi3d_disparity_tensor);
60 | }
61 |
62 | if (!bi3d_disparity_tensor.value()->data()) {
63 | GXF_LOG_ERROR("Failed to get pointer to bi3d disparity data");
64 | return gxf::ToResultCode(bi3d_disparity_tensor.value()->data());
65 | }
66 | const float* bi3d_disparity_data_ptr = bi3d_disparity_tensor.value()->data().value();
67 |
68 | // Get dimensions of tensor
69 | gxf::Shape dims = bi3d_disparity_tensor.value()->shape();
70 | const int image_height = dims.dimension(1);
71 | const int image_width = dims.dimension(2);
72 | const int image_size = dims.dimension(1) * dims.dimension(2);
73 |
74 | // Create output message
75 | auto out_message = gxf::Entity::New(context());
76 | if (!out_message) {
77 | GXF_LOG_ERROR("Failed to allocate message");
78 | return gxf::ToResultCode(out_message);
79 | }
80 |
81 | // Create video buffer
82 | auto out_video_buffer = out_message->add();
83 | if (!out_video_buffer) {
84 | GXF_LOG_ERROR("Failed to allocate output video buffer");
85 | return gxf::ToResultCode(out_video_buffer);
86 | }
87 |
88 | // Allocate video buffer on device (unpadded d32f)
89 | auto maybe_allocation = AllocateUnpaddedVideoBuffer(
90 | out_video_buffer.value(), image_width, image_height, gxf::MemoryStorageType::kDevice,
91 | pool_.get());
92 | if (!maybe_allocation) {
93 | GXF_LOG_ERROR("Failed to allocate output video buffer's memory.");
94 | return gxf::ToResultCode(maybe_allocation);
95 | }
96 |
97 | cudaMemset(out_video_buffer.value()->pointer(), 0,
98 | image_size * bi3d_disparity_tensor.value()->bytes_per_element());
99 |
100 | for (uint32_t i = 0; i < disparity_values_.get().size(); i++) {
101 | cuda_postprocess(bi3d_disparity_data_ptr + (i * image_size),
102 | reinterpret_cast(out_video_buffer.value()->pointer()),
103 | disparity_values_.get().at(i), image_height, image_width);
104 | }
105 |
106 | // Add timestamp to message if it is available from input message
107 | std::string timestamp_name{"timestamp"};
108 | auto maybe_bi3d_timestamp = bi3d_message->get();
109 | if (maybe_bi3d_timestamp) {
110 | auto out_timestamp = out_message.value().add(timestamp_name.c_str());
111 | if (!out_timestamp) {
112 | return GXF_FAILURE;
113 | }
114 | *out_timestamp.value() = *maybe_bi3d_timestamp.value();
115 | }
116 |
117 | // Publish message
118 | auto result = output_transmitter_->publish(out_message.value());
119 | if (!result) {
120 | return gxf::ToResultCode(result);
121 | }
122 |
123 | return GXF_SUCCESS;
124 | }
125 |
126 | } // namespace bi3d
127 | } // namespace isaac
128 | } // namespace nvidia
129 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_postprocessor.cu:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
3 |
4 | NVIDIA CORPORATION and its licensors retain all intellectual property
5 | and proprietary rights in and to this software, related documentation
6 | and any modifications thereto. Any use, reproduction, disclosure or
7 | distribution of this software and related documentation without an express
8 | license agreement from NVIDIA CORPORATION is strictly prohibited.
9 | */
10 | #include "extensions/bi3d/components/bi3d_postprocessor.cu.hpp"
11 |
12 | namespace nvidia {
13 | namespace isaac {
14 | namespace bi3d {
15 |
16 | __global__ void postprocessing_kernel(const float* input, float* output, int disparity,
17 | int imageHeight, int imageWidth) {
18 | const uint32_t x = blockIdx.x * blockDim.x + threadIdx.x;
19 | const uint32_t y = blockIdx.y * blockDim.y + threadIdx.y;
20 | const uint32_t index = y * imageWidth + x;
21 | if (x < imageWidth && y < imageHeight) {
22 | if (input[index] == 1.0) {
23 | output[index] = input[index] * disparity;
24 | }
25 | }
26 | }
27 |
28 | uint16_t ceil_div(uint16_t numerator, uint16_t denominator) {
29 | uint32_t accumulator = numerator + denominator - 1;
30 | return accumulator / denominator;
31 | }
32 |
33 | void cuda_postprocess(const float* input, float* output, int disparity, int imageHeight,
34 | int imageWidth) {
35 | dim3 block(16, 16);
36 | dim3 grid(ceil_div(imageWidth, 16), ceil_div(imageHeight, 16), 1);
37 | postprocessing_kernel<<>>(input, output, disparity, imageHeight, imageWidth);
38 | }
39 |
40 | } // namespace bi3d
41 | } // namespace isaac
42 | } // namespace nvidia
43 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_postprocessor.cu.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #pragma once
18 |
19 | #include
20 | #include
21 |
22 | #include "cuda.h"
23 | #include "cuda_runtime.h"
24 |
25 | namespace nvidia {
26 | namespace isaac {
27 | namespace bi3d {
28 |
29 | void cuda_postprocess(const float* input, float* output, int disparity, int imageHeight,
30 | int imageWidth);
31 |
32 | } // namespace bi3d
33 | } // namespace isaac
34 | } // namespace nvidia
35 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_postprocessor.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #pragma once
18 |
19 | #include
20 |
21 | #include "gxf/std/allocator.hpp"
22 | #include "gxf/std/codelet.hpp"
23 | #include "gxf/std/receiver.hpp"
24 | #include "gxf/std/transmitter.hpp"
25 |
26 | namespace nvidia {
27 | namespace isaac {
28 | namespace bi3d {
29 |
30 | // GXF codelet that takes Bi3D output tensor list and collapses it into single segmentation image
31 | class Bi3DPostprocessor : public gxf::Codelet {
32 | public:
33 | gxf_result_t registerInterface(gxf::Registrar* registrar) noexcept override;
34 | gxf_result_t start() noexcept override { return GXF_SUCCESS; }
35 | gxf_result_t tick() noexcept override;
36 | gxf_result_t stop() noexcept override { return GXF_SUCCESS; }
37 |
38 | private:
39 | gxf::Parameter> bi3d_receiver_;
40 | gxf::Parameter> output_transmitter_;
41 |
42 | gxf::Parameter> pool_;
43 | gxf::Parameter> disparity_values_;
44 | };
45 |
46 | } // namespace bi3d
47 | } // namespace isaac
48 | } // namespace nvidia
49 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/components/bi3d_postprocessor_utils.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #pragma once
18 |
19 | #include
20 |
21 | #include "gxf/multimedia/video.hpp"
22 | #include "gxf/std/allocator.hpp"
23 |
24 | namespace nvidia {
25 | namespace isaac {
26 | namespace bi3d {
27 |
28 | template
29 | inline constexpr uint8_t GetChannelSize();
30 |
31 | template <>
32 | inline constexpr uint8_t GetChannelSize() {
33 | return 1;
34 | }
35 |
36 | template <>
37 | inline constexpr uint8_t GetChannelSize() {
38 | return 4;
39 | }
40 |
41 | template <>
42 | inline constexpr uint8_t GetChannelSize() {
43 | return 3;
44 | }
45 |
46 | template
47 | inline const char* GetColorName();
48 |
49 | template <>
50 | inline const char* GetColorName() {
51 | return "gray";
52 | }
53 |
54 | template <>
55 | inline const char* GetColorName() {
56 | return "D";
57 | }
58 |
59 | template <>
60 | inline const char* GetColorName() {
61 | return "RGB";
62 | }
63 |
64 | template
65 | gxf::Expected AllocateVideoBuffer(gxf::Handle video_buffer, size_t width,
66 | size_t height, gxf::MemoryStorageType memory_storage_type,
67 | gxf::Handle allocator) {
68 | if (width % 2 != 0 || height % 2 != 0) {
69 | GXF_LOG_ERROR("Image width and height must be even, but received width: %zu, height: %zu",
70 | width, height);
71 | return gxf::Unexpected{GXF_FAILURE};
72 | }
73 |
74 | std::array planes{
75 | gxf::ColorPlane(GetColorName(), GetChannelSize(), GetChannelSize() * width)};
76 | gxf::VideoFormatSize video_format_size;
77 | const uint64_t size = video_format_size.size(width, height, planes);
78 | const std::vector planes_filled{planes.begin(), planes.end()};
79 | const gxf::VideoBufferInfo buffer_info{static_cast(width),
80 | static_cast(height), T, planes_filled,
81 | gxf::SurfaceLayout::GXF_SURFACE_LAYOUT_PITCH_LINEAR};
82 | return video_buffer->resizeCustom(buffer_info, size, memory_storage_type, allocator);
83 | }
84 |
85 | } // namespace bi3d
86 | } // namespace isaac
87 | } // namespace nvidia
88 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/inference/Bi3D.h:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 |
23 | #include "extensions/bi3d/inference/Model.h"
24 | #include "extensions/tensorops/core/Array.h"
25 | #include "extensions/tensorops/core/ComputeEngine.h"
26 | #include "extensions/tensorops/core/Tensor.h"
27 | #include "gems/dnn_inferencer/inferencer/Inferencer.h"
28 |
29 | namespace nvidia {
30 | namespace isaac {
31 | namespace bi3d {
32 |
33 | using TensorLayout = cvcore::tensor_ops::TensorLayout;
34 | using ChannelType = cvcore::tensor_ops::ChannelType;
35 | using ChannelCount = cvcore::tensor_ops::ChannelCount;
36 | using ImagePreProcessingParams = cvcore::tensor_ops::ImagePreProcessingParams;
37 | using Tensor_HWC_C3_U8 = cvcore::tensor_ops::Tensor;
39 | using Tensor_CHW_C3_F32 = cvcore::tensor_ops::Tensor;
41 | using Tensor_CHW_CX_U8 = cvcore::tensor_ops::Tensor;
43 | using Tensor_CHW_CX_F32 = cvcore::tensor_ops::Tensor;
45 | using DisparityLevels = cvcore::tensor_ops::Array;
46 | using TensorBase = cvcore::tensor_ops::TensorBase;
47 |
48 | enum class ProcessingControl : std::uint8_t {
49 | DISABLE = 0,
50 | ENABLE = 1
51 | };
52 |
53 | /**
54 | * Interface for Loading and running inference on bi3d network.
55 | */
56 | class Bi3D {
57 | public:
58 | using InferencerParams = cvcore::inferencer::TensorRTInferenceParams;
59 | using TRTInferenceType = cvcore::inferencer::TRTInferenceType;
60 |
61 | /**
62 | * Default Image Processing Params for Bi3D.
63 | */
64 | static const ImagePreProcessingParams defaultPreProcessorParams;
65 |
66 | /**
67 | * Default Model Input Params for Bi3D.
68 | */
69 | static const ModelInputParams defaultModelInputParams;
70 |
71 | /**
72 | * Default inference Params for Bi3D.
73 | */
74 | static const InferencerParams defaultFeatureParams;
75 | static const InferencerParams defaultHRParams;
76 | static const InferencerParams defaultRefinementParams;
77 | static const InferencerParams defaultSegmentationParams;
78 |
79 | /**
80 | * Bi3D extra params
81 | */
82 | struct Bi3DParams {
83 | // Maximum pixel-wise shift between left and right images
84 | std::size_t maxDisparityLevels;
85 | // Switch to turn on/off edge refinement models (FeatNetHR and RefineNet)
86 | // in inferencing
87 | ProcessingControl edgeRefinement;
88 | // Switch to turn on/off sigmoid operation in postprocessing
89 | ProcessingControl sigmoidPostProcessing;
90 | // Switch to turn on/off thresholding in postprocessing
91 | ProcessingControl thresholdPostProcessing;
92 | // The low value set by threshold postprocessing
93 | float thresholdValueLow;
94 | // The high value set by threshold postprocessing
95 | float thresholdValueHigh;
96 | // The threshold value that casts pixel values to either low or high
97 | float threshold;
98 | };
99 | static const Bi3DParams defaultBi3DParams;
100 |
101 | /**
102 | * Defaule Constructor of Bi3D.
103 | */
104 | Bi3D() = delete;
105 |
106 | /**
107 | * Constructor of Bi3D.
108 | * @param params custom params for the network.
109 | */
110 | Bi3D(const ImagePreProcessingParams & preProcessorParams,
111 | const ModelInputParams & modelInputParams,
112 | const InferencerParams & featureParams,
113 | const InferencerParams & hrParams,
114 | const InferencerParams & refinementParams,
115 | const InferencerParams & segmentationParams,
116 | const Bi3DParams & bi3dParams,
117 | cudaStream_t stream = 0);
118 |
119 | /**
120 | * Destructor of Bi3D.
121 | */
122 | ~Bi3D();
123 |
124 | /**
125 | * Main interface to run inference.
126 | * @param quantizedDisparity depth segmentation for input left and right images
127 | * @param leftImage left image tensor in RGB HWC format.
128 | * @param rightImage right image tensor in RGB HWC format.
129 | * @param disparityLevels diparity value to run depth estimation based on.
130 | */
131 | void execute(Tensor_CHW_CX_U8 & quantizedDisparity,
132 | const Tensor_HWC_C3_U8 & leftImage,
133 | const Tensor_HWC_C3_U8 & rightImage,
134 | const DisparityLevels& disparityLevels,
135 | cudaStream_t stream = 0);
136 |
137 | /**
138 | * Main interface to run inference.
139 | * @param disparityConfidence depth segmentation for input left and right images
140 | * @param leftImage left image tensor in RGB HWC format.
141 | * @param rightImage right image tensor in RGB HWC format.
142 | * @param disparityLevels diparity value to run depth estimation based on.
143 | */
144 | void execute(Tensor_CHW_CX_F32 & disparityConfidence,
145 | const Tensor_HWC_C3_U8 & leftImage,
146 | const Tensor_HWC_C3_U8 & rightImage,
147 | const DisparityLevels& disparityLevels,
148 | cudaStream_t stream = 0);
149 |
150 | /**
151 | * Main interface to run inference.
152 | * @param disparityConfidence depth segmentation for input left and right images
153 | * @param leftImage left image tensor in RGB CHW format.
154 | * @param rightImage right image tensor in RGB CHW format.
155 | * @param disparityLevels diparity value to run depth estimation based on.
156 | */
157 | void execute(Tensor_CHW_CX_F32 & disparityConfidence,
158 | const Tensor_CHW_C3_F32 & leftImage,
159 | const Tensor_CHW_C3_F32 & rightImage,
160 | const DisparityLevels& disparityLevels,
161 | cudaStream_t stream = 0);
162 |
163 | private:
164 | struct Bi3DImpl;
165 |
166 | std::unique_ptr m_pImpl;
167 | };
168 |
169 | /**
170 | * Interface for running pre-processing for Bi3D.
171 | */
172 | class Bi3DPreProcessor {
173 | public:
174 | /**
175 | * Removing the default constructor for Bi3DPreProcessor.
176 | */
177 | Bi3DPreProcessor() = delete;
178 |
179 | /**
180 | * Constructor for Bi3DPreProcessor.
181 | * @param preProcessorParams Image preprocessing parameters.
182 | * @param modelInputParams Model input parameters.
183 | */
184 | Bi3DPreProcessor(const ImagePreProcessingParams & preProcessorParams,
185 | const ModelInputParams & modelInputParams,
186 | cudaStream_t stream = 0);
187 |
188 | /**
189 | * Destructor for Bi3DPreProcessor.
190 | */
191 | ~Bi3DPreProcessor();
192 |
193 | void execute(Tensor_CHW_C3_F32 & preprocessedLeftImage,
194 | Tensor_CHW_C3_F32 & preprocessedRightImage,
195 | const Tensor_HWC_C3_U8 & leftImage,
196 | const Tensor_HWC_C3_U8 & rightImage,
197 | cudaStream_t stream = 0);
198 |
199 | void execute(Tensor_CHW_C3_F32 & preprocessedLeftImage,
200 | Tensor_CHW_C3_F32 & preprocessedRightImage,
201 | const Tensor_CHW_C3_F32 & leftImage,
202 | const Tensor_CHW_C3_F32 & rightImage,
203 | cudaStream_t stream = 0);
204 |
205 | private:
206 | struct Bi3DPreProcessorImpl;
207 |
208 | std::unique_ptr m_pImpl;
209 | };
210 |
211 | /**
212 | * Interface for running post-processing for Bi3D.
213 | */
214 | class Bi3DPostProcessor {
215 | public:
216 | /**
217 | * Removing the default constructor for Bi3DPostProcessor.
218 | */
219 | Bi3DPostProcessor() = delete;
220 |
221 | /**
222 | * Constructor for Bi3DPostProcessor.
223 | * @param modelInputParams Model input parameters.
224 | * @param bi3dParams Model parameters unique to this model.
225 | */
226 | Bi3DPostProcessor(const ModelInputParams & modelInputParams,
227 | const Bi3D::Bi3DParams & bi3dParams,
228 | cudaStream_t stream = 0);
229 |
230 | /**
231 | * Destructor for Bi3DPostProcessor.
232 | */
233 | ~Bi3DPostProcessor();
234 |
235 | void execute(Tensor_CHW_CX_F32 & disparityConfidence,
236 | Tensor_CHW_CX_F32 & rawDisparityConfidence,
237 | cudaStream_t stream = 0);
238 |
239 | private:
240 | struct Bi3DPostProcessorImpl;
241 |
242 | std::unique_ptr m_pImpl;
243 | };
244 |
245 | } // namespace bi3d
246 | } // namespace isaac
247 | } // namespace nvidia
248 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/inference/Bi3DPostProcessor.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include
19 |
20 | #include
21 | #include "extensions/bi3d/inference/Bi3D.h"
22 | #include "extensions/bi3d/inference/Bi3D_detail.hpp"
23 | #include "extensions/tensorops/core/Memory.h"
24 |
25 | namespace nvidia {
26 | namespace isaac {
27 | namespace bi3d {
28 |
29 | struct Bi3DPostProcessor::Bi3DPostProcessorImpl {
30 | mutable DisparityConfidence m_disparityConfidenceDevice;
31 | mutable DisparityConfidence m_disparityConfidenceThresholdDevice;
32 | mutable DisparityConfidence m_disparityConfidenceResizeDevice;
33 |
34 | ModelInputParams m_modelParams;
35 | Bi3D::Bi3DParams m_params;
36 |
37 | Bi3DPostProcessorImpl(const ModelInputParams & modelInputParams,
38 | const Bi3D::Bi3DParams & bi3dParams,
39 | cudaStream_t stream)
40 | : m_modelParams{modelInputParams}, m_params{bi3dParams}
41 | {
42 | m_disparityConfidenceDevice = {modelInputParams.inputLayerWidth,
43 | modelInputParams.inputLayerHeight,
44 | bi3dParams.maxDisparityLevels,
45 | false};
46 |
47 | m_disparityConfidenceThresholdDevice = {modelInputParams.inputLayerWidth,
48 | modelInputParams.inputLayerHeight,
49 | bi3dParams.maxDisparityLevels,
50 | false};
51 | }
52 |
53 | void resizeBuffers(std::size_t width, std::size_t height) {
54 | if (m_disparityConfidenceResizeDevice.getDimCount() > 0 &&
55 | m_disparityConfidenceResizeDevice.getWidth() == width &&
56 | m_disparityConfidenceResizeDevice.getHeight() == height) {
57 | return;
58 | }
59 |
60 | m_disparityConfidenceResizeDevice = {width, height,
61 | m_disparityConfidenceDevice.getChannelCount(),
62 | false};
63 | }
64 | };
65 |
66 | // =============================================================================
67 | // Bi3D Frontend
68 | // =============================================================================
69 |
70 | Bi3DPostProcessor::Bi3DPostProcessor(const ModelInputParams & modelInputParams,
71 | const Bi3D::Bi3DParams & bi3dParams,
72 | cudaStream_t stream)
73 | : m_pImpl{new Bi3DPostProcessorImpl(modelInputParams, bi3dParams, stream)} {}
74 |
75 | Bi3DPostProcessor::~Bi3DPostProcessor() {}
76 |
77 | void Bi3DPostProcessor::execute(DisparityConfidence & disparityConfidence,
78 | DisparityConfidence & rawDisparityConfidence,
79 | cudaStream_t stream) {
80 | // Ensuring the buffers are appropreately allocated
81 | m_pImpl->resizeBuffers(disparityConfidence.getWidth(), disparityConfidence.getHeight());
82 | if (m_pImpl->m_params.sigmoidPostProcessing == ProcessingControl::ENABLE) {
83 | Sigmoid(m_pImpl->m_disparityConfidenceDevice,
84 | rawDisparityConfidence, stream);
85 |
86 | if (m_pImpl->m_params.thresholdPostProcessing == ProcessingControl::ENABLE) {
87 | Threshold(m_pImpl->m_disparityConfidenceThresholdDevice,
88 | m_pImpl->m_disparityConfidenceDevice,
89 | m_pImpl->m_params.thresholdValueLow,
90 | m_pImpl->m_params.thresholdValueHigh,
91 | m_pImpl->m_params.threshold, stream);
92 |
93 | Resize(m_pImpl->m_disparityConfidenceResizeDevice,
94 | m_pImpl->m_disparityConfidenceThresholdDevice,
95 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
96 | } else {
97 | Resize(m_pImpl->m_disparityConfidenceResizeDevice,
98 | m_pImpl->m_disparityConfidenceDevice,
99 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
100 | }
101 | } else {
102 | if (m_pImpl->m_params.thresholdPostProcessing == ProcessingControl::ENABLE) {
103 | Threshold(m_pImpl->m_disparityConfidenceThresholdDevice,
104 | rawDisparityConfidence,
105 | m_pImpl->m_params.thresholdValueLow,
106 | m_pImpl->m_params.thresholdValueHigh,
107 | m_pImpl->m_params.threshold, stream);
108 |
109 | Resize(m_pImpl->m_disparityConfidenceResizeDevice,
110 | m_pImpl->m_disparityConfidenceThresholdDevice,
111 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
112 | } else {
113 | Resize(m_pImpl->m_disparityConfidenceResizeDevice,
114 | rawDisparityConfidence,
115 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
116 | }
117 | }
118 | DisparityConfidence partial{disparityConfidence.getWidth(),
119 | disparityConfidence.getHeight(),
120 | disparityConfidence.getChannelCount(),
121 | m_pImpl->m_disparityConfidenceResizeDevice.getData(),
122 | m_pImpl->m_disparityConfidenceResizeDevice.isCPU()};
123 | Copy(disparityConfidence, partial, stream);
124 | }
125 | } // namespace bi3d
126 | } // namespace isaac
127 | } // namespace nvidia
128 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/inference/Bi3DPreProcessor.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include
19 |
20 | #include
21 | #include "extensions/bi3d/inference/Bi3D.h"
22 | #include "extensions/bi3d/inference/Bi3D_detail.hpp"
23 | #include "extensions/bi3d/inference/Model.h"
24 | #include "extensions/tensorops/core/Memory.h"
25 |
26 | namespace nvidia {
27 | namespace isaac {
28 | namespace bi3d {
29 |
30 | struct Bi3DPreProcessor::Bi3DPreProcessorImpl {
31 | mutable InputImage m_leftImageDevice;
32 | mutable InputImage m_rightImageDevice;
33 | mutable PreprocessedImage m_preLeftImageDevice;
34 | mutable PreprocessedImage m_preRightImageDevice;
35 | mutable InputImage m_leftImageResizeDevice;
36 | mutable InputImage m_rightImageResizeDevice;
37 |
38 | // Operation(s)
39 | NormalizeFunctor m_normalizer;
40 |
41 | // Needed parameters for pre-processing
42 | ImagePreProcessingParams m_preProcessorParams;
43 | ModelInputParams m_modelParams;
44 |
45 | Bi3DPreProcessorImpl(const ImagePreProcessingParams & preProcessorParams,
46 | const ModelInputParams & modelInputParams,
47 | cudaStream_t stream)
48 | : m_preProcessorParams{preProcessorParams},
49 | m_modelParams{modelInputParams},
50 | m_normalizer{static_cast(modelInputParams.inputLayerWidth),
51 | static_cast(modelInputParams.inputLayerHeight)} {
52 | // Configuring the top-level model input(s)
53 | m_leftImageResizeDevice = {modelInputParams.inputLayerWidth,
54 | modelInputParams.inputLayerHeight,
55 | false};
56 | m_rightImageResizeDevice = {modelInputParams.inputLayerWidth,
57 | modelInputParams.inputLayerHeight,
58 | m_leftImageResizeDevice.isCPU()};
59 | }
60 |
61 | void resizeBuffers(std::size_t width, std::size_t height) {
62 | if (m_leftImageDevice.getDimCount() > 0 &&
63 | m_leftImageDevice.getWidth() == width &&
64 | m_leftImageDevice.getHeight() == height) {
65 | return;
66 | }
67 |
68 | m_leftImageDevice = {width, height, false};
69 | m_rightImageDevice = {width, height, false};
70 | m_preLeftImageDevice = {width, height, false};
71 | m_preRightImageDevice = {width, height, false};
72 | }
73 | };
74 |
75 | // =============================================================================
76 | // Bi3D Frontend
77 | // =============================================================================
78 |
79 | Bi3DPreProcessor::Bi3DPreProcessor(const ImagePreProcessingParams & preProcessorParams,
80 | const ModelInputParams & modelInputParams,
81 | cudaStream_t stream)
82 | : m_pImpl{new Bi3DPreProcessorImpl(preProcessorParams, modelInputParams, stream)} {}
83 |
84 | Bi3DPreProcessor::~Bi3DPreProcessor() {}
85 |
86 | void Bi3DPreProcessor::execute(PreprocessedImage & preprocessedLeftImage,
87 | PreprocessedImage & preprocessedRightImage,
88 | const InputImage & leftImage,
89 | const InputImage & rightImage,
90 | cudaStream_t stream) {
91 | // Ensuring the buffers are appropreately allocated
92 | m_pImpl->resizeBuffers(leftImage.getWidth(), leftImage.getHeight());
93 |
94 | // Ensuring data is on the GPU
95 | // FIXME: Rename so this is not confused with cvcore::Copy
96 | Copy(m_pImpl->m_leftImageDevice, leftImage, stream);
97 | Copy(m_pImpl->m_rightImageDevice, rightImage, stream);
98 |
99 | // Resizing the data to model input size
100 | Resize(m_pImpl->m_leftImageResizeDevice, m_pImpl->m_leftImageDevice,
101 | false, cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
102 | Resize(m_pImpl->m_rightImageResizeDevice, m_pImpl->m_rightImageDevice,
103 | false, cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
104 |
105 | // Normalize (data whiten) the images
106 | m_pImpl->m_normalizer(preprocessedLeftImage, m_pImpl->m_leftImageResizeDevice,
107 | m_pImpl->m_preProcessorParams.pixelMean,
108 | m_pImpl->m_preProcessorParams.stdDev,
109 | stream);
110 | m_pImpl->m_normalizer(preprocessedRightImage, m_pImpl->m_rightImageResizeDevice,
111 | m_pImpl->m_preProcessorParams.pixelMean,
112 | m_pImpl->m_preProcessorParams.stdDev,
113 | stream);
114 | }
115 |
116 | void Bi3DPreProcessor::execute(PreprocessedImage & preprocessedLeftImage,
117 | PreprocessedImage & preprocessedRightImage,
118 | const PreprocessedImage & leftImage,
119 | const PreprocessedImage & rightImage,
120 | cudaStream_t stream) {
121 | // Ensuring the buffers are appropreately allocated
122 | m_pImpl->resizeBuffers(leftImage.getWidth(), leftImage.getHeight());
123 |
124 | // FIXME: Rename so this is not confused with cvcore::Copy
125 | Copy(m_pImpl->m_preLeftImageDevice, leftImage, stream);
126 | Copy(m_pImpl->m_preRightImageDevice, rightImage, stream);
127 |
128 | // Resizing the data to model input size
129 | Resize(preprocessedLeftImage, m_pImpl->m_preLeftImageDevice,
130 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
131 | Resize(preprocessedLeftImage, m_pImpl->m_preRightImageDevice,
132 | cvcore::tensor_ops::InterpolationType::INTERP_LINEAR, stream);
133 | }
134 | } // namespace bi3d
135 | } // namespace isaac
136 | } // namespace nvidia
137 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/inference/Bi3D_detail.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include "extensions/bi3d/inference/Bi3D_detail.hpp"
19 |
20 | #include
21 | #include
22 | #include
23 | #include
24 | #include
25 | #include
26 |
27 | namespace nvidia {
28 | namespace isaac {
29 | namespace bi3d {
30 |
31 | void _pad(Tensor_CHW_C1_F32& dst, const Tensor_CHW_C1_F32& src,
32 | int topBorderHeight, int leftBorderWidth, cudaStream_t stream) {
33 | // Using NPP function: ``nppiCopyConstBorder_32f_C1R_Ctx''
34 | // Spec ==> NppStatus nppiCopyConstBorder_32f_C1R_Ctx(const Npp32f * pSrc,
35 | // int nSrcStep,
36 | // NppiSize oSrcSizeROI,
37 | // Npp32f * pDst,
38 | // int nDstStep,
39 | // NppiSize oDstSizeROI,
40 | // int nTopBorderHeight,
41 | // int nLeftBorderWidth,
42 | // Npp32f nValue,
43 | // NppStreamContext nppStreamCtx)
44 | //
45 | // Parameters
46 | // pSrc Source-Image Pointer.
47 | // nSrcStep Source-Image Stride in bytes.
48 | // oSrcSizeROI Size (width, height) of the source region in pixels.
49 | // pDst Destination-Image Pointer.
50 | // nDstStep Destination-Image Stride in bytes.
51 | // oDstSizeROI Size (width, height) of the destination region, i.e. the region
52 | // that gets filled with data from the source image (inner part)
53 | // and constant border color (outer part).
54 | // nTopBorderHeight Height (in pixels) of the top border. The number of pixel rows at
55 | // the top of the destination ROI that will be filled with the
56 | // constant border color. nBottomBorderHeight = oDstSizeROI.height -
57 | // nTopBorderHeight - oSrcSizeROI.height.
58 | // nLeftBorderWidth Width (in pixels) of the left border. The width of the border at
59 | // the right side of the destination ROI is implicitly defined by the
60 | // size of the source ROI: nRightBorderWidth = oDstSizeROI.width -
61 | // nLeftBorderWidth - oSrcSizeROI.width.
62 | // nValue The pixel value to be set for border pixels for single channel
63 | // functions.
64 | // nppStreamCtx NPP Application Managed Stream Context.
65 | nppiCopyConstBorder_32f_C1R_Ctx(
66 | static_cast(src.getData()),
67 | src.getStride(TensorDimension::HEIGHT) * sizeof(float),
68 | {static_cast(src.getWidth()), static_cast(src.getHeight())},
69 | static_cast(dst.getData()),
70 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
71 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
72 | topBorderHeight, leftBorderWidth, 0.0, cvcore::tensor_ops::GetNppStreamContext(stream));
73 | }
74 |
75 | void _threshold(Tensor_CHW_C1_F32& dst, const Tensor_CHW_C1_F32& src,
76 | float valueLow, float valueHigh, float thresholdValue,
77 | cudaStream_t stream) {
78 | // Using NPP function: ``nppiThreshold_LTValGTVal_32f_C1R_Ctx''
79 | // Spec ==> NppStatus nppiThreshold_LTValGTVal_32f_C1R_Ctx(const Npp32f * pSrc,
80 | // int nSrcStep,
81 | // Npp32f * pDst,
82 | // int nDstStep,
83 | // NppiSize oSizeROI,
84 | // Npp32f nThresholdLT,
85 | // Npp32f nValueLT,
86 | // Npp32f nThresholdGT,
87 | // Npp32f nValueGT,
88 | // NppStreamContext nppStreamCtx)
89 | //
90 | // Parameters
91 | // pSrc Source-Image Pointer.
92 | // nSrcStep Source-Image Stride in bytes.
93 | // pDst Destination-Image Pointer.
94 | // nDstStep Destination-Image Stride in bytes.
95 | // oSizeROI Size (width, height) of the destination region, i.e. the region
96 | // that gets filled with data from the source image
97 | // nThresholdLT The thresholdLT value.
98 | // nValueLT The thresholdLT replacement value.
99 | // nThresholdGT The thresholdGT value.
100 | // nValueGT The thresholdGT replacement value.
101 | // nppStreamCtx NPP Application Managed Stream Context.
102 | nppiThreshold_LTValGTVal_32f_C1R_Ctx(
103 | static_cast(src.getData()),
104 | src.getStride(TensorDimension::HEIGHT) * sizeof(float),
105 | static_cast(dst.getData()),
106 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
107 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
108 | thresholdValue * (1.0 + std::numeric_limits::epsilon()), valueLow,
109 | thresholdValue, valueHigh,
110 | cvcore::tensor_ops::GetNppStreamContext(stream));
111 | }
112 |
113 | void _clear(Tensor_CHW_C1_F32& dst, cudaStream_t stream) {
114 | // Using NPP function: ``nppiSet_32f_C1R_Ctx''
115 | // Spec ==> NppStatus nppiSet_32f_C1R_Ctx(const Npp32f nValue
116 | // Npp32f * pDst,
117 | // int nDstStep,
118 | // NppiSize oSizeROI,
119 | // NppStreamContext nppStreamCtx)
120 | //
121 | // Parameters
122 | // nValue The pixel value to be set.
123 | // pDst Destination-Image Pointer.
124 | // nDstStep Destination-Image Stride in bytes.
125 | // oSizeROI Size (width, height) of the destination region, i.e. the region that
126 | // gets filled with nValue.
127 | // nppStreamCtx NPP Application Managed Stream Context.
128 | nppiSet_32f_C1R_Ctx(
129 | 0.0,
130 | static_cast(dst.getData()),
131 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
132 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
133 | cvcore::tensor_ops::GetNppStreamContext(stream));
134 | }
135 |
136 | void _sigmoid(Tensor_CHW_C1_F32& dst, Tensor_CHW_C1_F32& src,
137 | cudaStream_t stream) {
138 | auto context = cvcore::tensor_ops::GetNppStreamContext(stream);
139 |
140 | // This is a bit of a complex series of operations, here's an exact model
141 | //
142 | // Explicit:
143 | // DST = exp(-1 * ln(1 + exp(-1 * SRC)))
144 | //
145 | // Properties:
146 | // 1) exp(ln(x)) = x
147 | // 2) ln(x^y) = y * ln(x)
148 | // 3) x^(-1) = 1 / x
149 | //
150 | // Expected:
151 | // DST = 1 / (1 + exp(-1 * SRC))
152 | nppiMulC_32f_C1R_Ctx(
153 | static_cast(src.getData()),
154 | src.getStride(TensorDimension::HEIGHT) * sizeof(float),
155 | -1.0,
156 | static_cast(dst.getData()),
157 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
158 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
159 | context);
160 | nppiExp_32f_C1IR_Ctx(
161 | static_cast(dst.getData()),
162 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
163 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
164 | context);
165 | nppiAddC_32f_C1IR_Ctx(
166 | 1.0,
167 | static_cast(dst.getData()),
168 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
169 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
170 | context);
171 | nppiLn_32f_C1IR_Ctx(
172 | static_cast(dst.getData()),
173 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
174 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
175 | context);
176 | nppiMulC_32f_C1IR_Ctx(
177 | -1.0,
178 | static_cast(dst.getData()),
179 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
180 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
181 | context);
182 | nppiExp_32f_C1IR_Ctx(
183 | static_cast(dst.getData()),
184 | dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
185 | {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
186 | context);
187 | }
188 |
189 | void _sigmoid(Tensor_CHW_C1_F32& dst, Tensor_CHW_C1_F32& src) {
190 | std::transform(src.getData(), src.getData() + src.getDataSize() / sizeof(float),
191 | dst.getData(), [](float value) -> float {
192 | return 1.0 / (1.0 + std::exp(-1.0 * value));});
193 | }
194 |
195 | } // namespace bi3d
196 | } // namespace isaac
197 | } // namespace nvidia
198 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/extensions/bi3d/inference/Model.h:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2020-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 |
23 | #include "extensions/tensorops/core/Image.h"
24 |
25 | namespace nvidia {
26 | namespace isaac {
27 | namespace bi3d {
28 |
29 | /**
30 | * Struct to describe input type required by the model
31 | */
32 | struct ModelInputParams {
33 | size_t maxBatchSize; /**< maxbatchSize supported by network*/
34 | size_t inputLayerWidth; /**< Input layer width */
35 | size_t inputLayerHeight; /**< Input layer Height */
36 | cvcore::tensor_ops::ImageType modelInputType; /**< Input Layout type */
37 | };
38 |
39 | /**
40 | * Struct to describe the model
41 | */
42 | struct ModelInferenceParams {
43 | std::string engineFilePath; /**< Engine file path. */
44 | std::vector inputLayers; /**< names of input layers. */
45 | std::vector outputLayers; /**< names of output layers. */
46 | };
47 |
48 | } // namespace bi3d
49 | } // namespace isaac
50 | } // namespace nvidia
51 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/Errors.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include "gems/dnn_inferencer/inferencer/Errors.h"
19 | #include
20 |
21 | #ifndef __cpp_lib_to_underlying
22 | namespace std {
23 | template
24 | constexpr underlying_type_t to_underlying(Enum e) noexcept {
25 | return static_cast>(e);
26 | }
27 | }; // namespace std
28 | #endif // __cpp_lib_to_underlying
29 |
30 | namespace cvcore {
31 | namespace inferencer {
32 |
33 | namespace detail {
34 | struct InferencerErrorCategory : std::error_category {
35 | const char* name() const noexcept final {
36 | return "cvcore-inferencer-error";
37 | }
38 |
39 | std::string message(int value) const final {
40 | std::string result;
41 |
42 | switch (value) {
43 | case std::to_underlying(InferencerErrorCode::SUCCESS):
44 | result = "(SUCCESS) No errors detected";
45 | break;
46 | case std::to_underlying(InferencerErrorCode::INVALID_ARGUMENT):
47 | result = "(INVALID_ARGUMENT) Invalid config parameter or input argument";
48 | break;
49 | case std::to_underlying(InferencerErrorCode::INVALID_OPERATION):
50 | result = "(INVALID_OPERATION) Invalid operation performed";
51 | break;
52 | case std::to_underlying(InferencerErrorCode::TRITON_SERVER_NOT_READY):
53 | result = "(TRITON_SERVER_NOT_READY) Triton server is not live or the serverUrl"
54 | "is incorrect";
55 | break;
56 | case std::to_underlying(InferencerErrorCode::TRITON_CUDA_SHARED_MEMORY_ERROR):
57 | result = "(TRITON_CUDA_SHARED_MEMORY_ERROR) Unable to map/unmap cuda shared memory"
58 | "for triton server";
59 | break;
60 | case std::to_underlying(InferencerErrorCode::TRITON_INFERENCE_ERROR):
61 | result = "(TRITON_INFERENCE_ERROR) Error during inference using triton API";
62 | break;
63 | case std::to_underlying(InferencerErrorCode::TRITON_REGISTER_LAYER_ERROR):
64 | result = "(TRITON_REGISTER_LAYER_ERROR) Error when setting input or output layers";
65 | break;
66 | case std::to_underlying(InferencerErrorCode::TENSORRT_INFERENCE_ERROR):
67 | result = "(TENSORRT_INFERENCE_ERROR) Error when running TensorRT enqueue/execute";
68 | break;
69 | default:
70 | result = "(Unrecognized Condition) Value " + std::to_string(value) +
71 | " does not map to known error code literal " +
72 | " defined by cvcore::inferencer::InferencerErrorCode";
73 | break;
74 | }
75 |
76 | return result;
77 | }
78 |
79 | std::error_condition default_error_condition(int code) const noexcept final {
80 | std::error_condition result;
81 | using ErrorCode = cvcore::tensor_ops::ErrorCode;
82 |
83 | switch (code) {
84 | case std::to_underlying(InferencerErrorCode::SUCCESS):
85 | result = ErrorCode::SUCCESS;
86 | break;
87 | case std::to_underlying(InferencerErrorCode::INVALID_ARGUMENT):
88 | result = ErrorCode::INVALID_ARGUMENT;
89 | break;
90 | case std::to_underlying(InferencerErrorCode::INVALID_OPERATION):
91 | result = ErrorCode::INVALID_OPERATION;
92 | break;
93 | case std::to_underlying(InferencerErrorCode::NOT_IMPLEMENTED):
94 | result = ErrorCode::NOT_IMPLEMENTED;
95 | break;
96 | case std::to_underlying(InferencerErrorCode::TRITON_SERVER_NOT_READY):
97 | result = ErrorCode::NOT_READY;
98 | break;
99 | case std::to_underlying(InferencerErrorCode::TRITON_CUDA_SHARED_MEMORY_ERROR):
100 | result = ErrorCode::DEVICE_ERROR;
101 | break;
102 | case std::to_underlying(InferencerErrorCode::TRITON_INFERENCE_ERROR):
103 | result = ErrorCode::INVALID_OPERATION;
104 | break;
105 | case std::to_underlying(InferencerErrorCode::TENSORRT_INFERENCE_ERROR):
106 | result = ErrorCode::INVALID_OPERATION;
107 | break;
108 | case std::to_underlying(InferencerErrorCode::TRITON_REGISTER_LAYER_ERROR):
109 | result = ErrorCode::INVALID_OPERATION;
110 | break;
111 | default:
112 | result = ErrorCode::NOT_IMPLEMENTED;
113 | break;
114 | }
115 |
116 | return result;
117 | }
118 | };
119 | } // namespace detail
120 |
121 | const detail::InferencerErrorCategory errorCategory{};
122 |
123 | std::error_code make_error_code(InferencerErrorCode ec) noexcept {
124 | return {std::to_underlying(ec), errorCategory};
125 | }
126 |
127 | } // namespace inferencer
128 | } // namespace cvcore
129 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/Errors.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 |
15 | #pragma once
16 |
17 | #include "extensions/tensorops/core/CVError.h"
18 |
19 | namespace cvcore {
20 | namespace inferencer {
21 |
22 | /*
23 | * Enum class describing the inference error codes.
24 | */
25 | enum class InferencerErrorCode : std::int32_t {
26 | SUCCESS = 0,
27 | INVALID_ARGUMENT,
28 | INVALID_OPERATION,
29 | NOT_IMPLEMENTED,
30 | TRITON_SERVER_NOT_READY,
31 | TRITON_CUDA_SHARED_MEMORY_ERROR,
32 | TRITON_INFERENCE_ERROR,
33 | TRITON_REGISTER_LAYER_ERROR,
34 | TENSORRT_INFERENCE_ERROR,
35 | TENSORRT_ENGINE_ERROR
36 | };
37 |
38 | } // namespace inferencer
39 | } // namespace cvcore
40 |
41 | namespace std {
42 |
43 | template<>
44 | struct is_error_code_enum : true_type {
45 | };
46 |
47 | } // namespace std
48 |
49 | namespace cvcore {
50 | namespace inferencer {
51 |
52 | std::error_code make_error_code(InferencerErrorCode) noexcept;
53 |
54 | } // namespace inferencer
55 | } // namespace cvcore
56 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/IInferenceBackend.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 |
15 | #pragma once
16 |
17 | #include
18 | #include
19 | #include
20 | #include
21 | #include
22 | #include
23 | #include
24 |
25 | #include
26 | #include "extensions/tensorops/core/Tensor.h"
27 |
28 | namespace cvcore {
29 | namespace inferencer {
30 |
31 | /**
32 | * Struct type to describe input and output layers.
33 | */
34 | struct LayerInfo {
35 | size_t index; /**< Block Index of layer */
36 | std::string name; /**< Name of layer */
37 | std::vector shape; /**< Shape of layer */
38 | cvcore::tensor_ops::ChannelType dataType; /**< Datatype of layer */
39 | cvcore::tensor_ops::TensorLayout layout; /**< Tensor layour of layer */
40 | size_t layerSize;
41 | };
42 |
43 | /**
44 | * Enum class to describe the backend protocol for triton
45 | */
46 | enum class BackendProtocol {
47 | GRPC,
48 | HTTP
49 | };
50 |
51 | /**
52 | * Struct type to describe the input for triton inference.
53 | */
54 | struct TritonRemoteInferenceParams {
55 | std::string serverUrl; /**< Server url created by running the triton server */
56 | bool verbose; /**< Verbose log from backend */
57 | BackendProtocol protocolType; /**< Backend protocol type */
58 | std::string modelName; /**< Model name as per model respoitory */
59 | std::string modelVersion; /** Model version as per model repository */
60 | };
61 |
62 | /**
63 | * Struct type to describe the model metadata parsed by the inference backend.
64 | */
65 | struct ModelMetaData {
66 | std::string modelName; /**< Model name */
67 | std::string modelVersion; /**< Model version */
68 | std::unordered_map inputLayers; /**< Map of input layer */
69 | std::unordered_map
70 | outputLayers; /**< Map of output layer information indexed by layer name */
71 | size_t maxBatchSize; /**< Maximum batch size */
72 | };
73 |
74 | /**
75 | * Enum type for TensorRT inference type
76 | */
77 | enum class TRTInferenceType {
78 | TRT_ENGINE, /**< Inference using TRT engine file */
79 | TRT_ENGINE_IN_MEMORY /**< Inference using TRT Cuda Engine */
80 | };
81 |
82 | /**
83 | * TRT Logger
84 | */
85 | class TRTLogger : public nvinfer1::ILogger {
86 | public:
87 | void log(Severity severity, const char* msg) noexcept {
88 | if ((severity == Severity::kERROR) || (severity == Severity::kWARNING)) {
89 | std::cerr << msg << std::endl;
90 | }
91 | }
92 | };
93 |
94 | /**
95 | * Enum class to describe the model build flags
96 | */
97 | enum OnnxModelBuildFlag {
98 | NONE = 0,
99 | kINT8 = 1,
100 | kFP16 = 2,
101 | kGPU_FALLBACK = 4,
102 | };
103 |
104 | /**
105 | * Struct type to describe the input for triton inference.
106 | */
107 | struct TensorRTInferenceParams {
108 | TRTInferenceType inferType; /**< TensorRT inference type */
109 | nvinfer1::ICudaEngine* engine; /**< Cuda engine file for TRT_ENGINE_IN_MEMORY type. */
110 | // Nullptr if TRT_ENGINE is used
111 | std::string onnxFilePath; /**< ONNX model file path. */
112 | std::string engineFilePath; /**< Engine file path for TRT_ENGINE type. */
113 | bool force_engine_update;
114 | int32_t buildFlags;
115 | int64_t max_workspace_size;
116 | std::size_t maxBatchSize; /**< Max Batch size */
117 | std::vector inputLayerNames; /** Input layer names */
118 | std::vector outputLayerNames; /** Output layer names */
119 | int32_t dlaID{-1};
120 | };
121 |
122 | /**
123 | * Interface for TritonRemote , Triton C and Native TensorRT inference backend.
124 | */
125 | class IInferenceBackendClient {
126 | public:
127 | virtual ~IInferenceBackendClient() noexcept = default;
128 |
129 | /**
130 | * Function to set input layer data
131 | * @param trtInputBuffer Input GPU buffer
132 | * @param inputLayerName Input Layer name
133 | * @return error code
134 | */
135 | virtual std::error_code setInput(const cvcore::tensor_ops::TensorBase& trtInputBuffer,
136 | std::string inputLayerName) = 0;
137 |
138 | /**
139 | * Function to set output layer data
140 | * @param trtInputBuffer Output GPU buffer
141 | * @param outputLayerName Output Layer name
142 | * @return error code
143 | */
144 | virtual std::error_code setOutput(cvcore::tensor_ops::TensorBase& trtOutputBuffer,
145 | std::string outputLayerName) = 0;
146 |
147 | /**
148 | * Returns the model metadata parsed by the inference backend.
149 | * @return ModelMetaData
150 | */
151 | virtual ModelMetaData getModelMetaData() const = 0;
152 |
153 | /**
154 | * Inference based on input and output set. enqueueV2 for TensorRT and inferSync for Triton.
155 | * @param Batch size of input for inference. Default set to 1. Must be <= Max Batch Size .
156 | * @return error code
157 | */
158 | virtual std::error_code infer(size_t batchSize = 1) = 0;
159 |
160 | /**
161 | * Sets the cuda stream applicable only for TensorRT backend.
162 | * @param cudaStream_t cuda input stream
163 | * @return error code
164 | */
165 | virtual std::error_code setCudaStream(cudaStream_t) = 0;
166 |
167 | /**
168 | * Unregisters the tensor mapped from the inference backend
169 | * @param input/output layer name
170 | * @return error code
171 | */
172 | virtual std::error_code unregister(std::string layerName) = 0;
173 |
174 | /**
175 | * Unregisters all the tensor mappeds from the inference backend
176 | * @return error code
177 | */
178 | virtual std::error_code unregister() = 0;
179 |
180 | protected:
181 | IInferenceBackendClient() = default;
182 | IInferenceBackendClient(const IInferenceBackendClient&) = default;
183 | IInferenceBackendClient& operator=(const IInferenceBackendClient&) = default;
184 | IInferenceBackendClient(IInferenceBackendClient &&) noexcept = default;
185 | IInferenceBackendClient& operator=(IInferenceBackendClient &&) noexcept = default;
186 | };
187 |
188 | using InferenceBackendClient = IInferenceBackendClient *;
189 |
190 | } // namespace inferencer
191 | } // namespace cvcore
192 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/Inferencer.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include "gems/dnn_inferencer/inferencer/Inferencer.h"
19 |
20 | #include
21 | #include
22 | #include
23 | #include
24 |
25 | #include "Errors.h"
26 | #include "IInferenceBackend.h"
27 | #include "TensorRTInferencer.h"
28 | #include "TritonGrpcInferencer.h"
29 |
30 | namespace cvcore {
31 | namespace inferencer {
32 | using ErrorCode = cvcore::tensor_ops::ErrorCode;
33 |
34 | std::mutex InferenceBackendFactory::inferenceMutex;
35 |
36 | #ifdef ENABLE_TRITON
37 | std::unordered_map>
38 | InferenceBackendFactory::tritonRemoteMap;
39 |
40 | std::error_code InferenceBackendFactory::CreateTritonRemoteInferenceBackendClient(
41 | InferenceBackendClient& client, const TritonRemoteInferenceParams& params) {
42 | std::lock_guard instanceLock(inferenceMutex);
43 |
44 | if (params.protocolType == BackendProtocol::HTTP) {
45 | return ErrorCode::NOT_IMPLEMENTED;
46 | }
47 | std::error_code result = ErrorCode::SUCCESS;
48 | std::string hashString = params.serverUrl + params.modelName + params.modelVersion;
49 |
50 | try {
51 | if (tritonRemoteMap.find(hashString) != tritonRemoteMap.end()) {
52 | client = tritonRemoteMap[hashString].second;
53 | tritonRemoteMap[hashString].first++;
54 | } else {
55 | tritonRemoteMap[hashString] =
56 | std::pair(1,
57 | new TritonGrpcInferencer(params));
58 | }
59 | }
60 | catch (std::error_code &e) {
61 | result = e;
62 | }
63 | catch (...) {
64 | result = ErrorCode::INVALID_ARGUMENT;
65 | }
66 | client = tritonRemoteMap[hashString].second;
67 | return result;
68 | }
69 |
70 | std::error_code InferenceBackendFactory::DestroyTritonRemoteInferenceBackendClient(
71 | InferenceBackendClient& client) {
72 | std::lock_guard instanceLock(inferenceMutex);
73 | for (auto &it : tritonRemoteMap) {
74 | if (it.second.second == client) {
75 | it.second.first--;
76 | if (it.second.first == 0) {
77 | tritonRemoteMap.erase(it.first);
78 | client->unregister();
79 | delete client;
80 | client = nullptr;
81 | }
82 | break;
83 | }
84 | }
85 | client = nullptr;
86 | return ErrorCode::SUCCESS;
87 | }
88 | #endif
89 |
90 | std::error_code InferenceBackendFactory::CreateTensorRTInferenceBackendClient(
91 | InferenceBackendClient& client, const TensorRTInferenceParams& params) {
92 |
93 | std::lock_guard instanceLock(inferenceMutex);
94 | std::error_code result = ErrorCode::SUCCESS;
95 | try {
96 | client = new TensorRTInferencer(params);
97 | }
98 | catch (std::error_code &e) {
99 | result = e;
100 | }
101 | catch (...) {
102 | result = ErrorCode::INVALID_ARGUMENT;
103 | }
104 | return result;
105 | }
106 |
107 | std::error_code InferenceBackendFactory::DestroyTensorRTInferenceBackendClient(
108 | InferenceBackendClient& client) {
109 |
110 | std::lock_guard instanceLock(inferenceMutex);
111 | if (client != nullptr) {
112 | client->unregister();
113 | delete client;
114 | client = nullptr;
115 | }
116 | client = nullptr;
117 |
118 | return ErrorCode::SUCCESS;
119 | }
120 | } // namespace inferencer
121 | } // namespace cvcore
122 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/Inferencer.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 |
15 | #pragma once
16 |
17 | #include
18 | #include
19 | #include
20 | #include
21 | #include
22 |
23 | #include "extensions/tensorops/core/Tensor.h"
24 | #include "IInferenceBackend.h"
25 |
26 | namespace cvcore {
27 | namespace inferencer {
28 |
29 | /**
30 | * A class to create and destroy a client for a given inference backend type
31 | */
32 | class InferenceBackendFactory {
33 | public:
34 | #ifdef ENABLE_TRITON
35 |
36 | /**
37 | * Function to create client for Triton remote inference backend based on the Triton remote
38 | * inference paramaters.
39 | * @param client client object created
40 | * @param Triton remote inference config parameters.
41 | * @return error code
42 | */
43 | static std::error_code CreateTritonRemoteInferenceBackendClient(InferenceBackendClient& client,
44 | const TritonRemoteInferenceParams&);
45 |
46 | /**
47 | * Function to Destroy the triton grpc client
48 | * @param client client object created
49 | * @return error code
50 | */
51 | static std::error_code DestroyTritonRemoteInferenceBackendClient(
52 | InferenceBackendClient& client);
53 | #endif
54 |
55 | /**
56 | * Function to create client for TensorRT inference backend based on the TensorRT
57 | * inference paramaters.
58 | * @param client client object created
59 | * @param TensorRT inference config parameters.
60 | * @return error code
61 | */
62 | static std::error_code CreateTensorRTInferenceBackendClient(InferenceBackendClient& client,
63 | const TensorRTInferenceParams&);
64 |
65 | /**
66 | * Function to Destroy the tensorrt client
67 | * @param client client object created
68 | * @return error code
69 | */
70 | static std::error_code DestroyTensorRTInferenceBackendClient(InferenceBackendClient& client);
71 |
72 | private:
73 | #ifdef ENABLE_TRITON
74 | // Keeps track of any changes in url/model repo path and returns an existing / new client
75 | // instance.
76 | static std::unordered_map> tritonRemoteMap;
78 | #endif
79 | static std::mutex inferenceMutex;
80 | };
81 |
82 | } // namespace inferencer
83 | } // namespace cvcore
84 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TensorRTInferencer.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2024, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 |
15 | #pragma once
16 |
17 | #include
18 | #include
19 | #include
20 | #include
21 |
22 | #include
23 | #include
24 | #include "Errors.h"
25 | #include "IInferenceBackend.h"
26 | #include "Inferencer.h"
27 |
28 | namespace cvcore {
29 | namespace inferencer {
30 |
31 | using TensorBase = cvcore::tensor_ops::TensorBase;
32 | class TensorRTInferencer : public IInferenceBackendClient {
33 | public:
34 | TensorRTInferencer(const TensorRTInferenceParams& params);
35 |
36 | // Set input layer tensor
37 | std::error_code setInput(const TensorBase& trtInputBuffer,
38 | std::string inputLayerName) override;
39 |
40 | // Sets output layer tensor
41 | std::error_code setOutput(TensorBase& trtOutputBuffer,
42 | std::string outputLayerName) override;
43 |
44 | // Get the model metadata parsed based on the model file
45 | // This would be done in initialize call itself. User can access the
46 | // modelMetaData created using this API.
47 | ModelMetaData getModelMetaData() const override;
48 |
49 | // Convert onnx mode to engine file
50 | std::error_code convertModelToEngine(int32_t dla_core,
51 | const char* model_file, int64_t max_workspace_size, int32_t buildFlags,
52 | std::size_t max_batch_size);
53 |
54 | // TensorRT will use infer and TensorRT would use enqueueV2
55 | std::error_code infer(size_t batchSize = 1) override;
56 |
57 | // Applicable only for Native TRT
58 | std::error_code setCudaStream(cudaStream_t) override;
59 |
60 | // Unregister shared memory for layer
61 | std::error_code unregister(std::string layerName) override;
62 |
63 | // Unregister all shared memory
64 | std::error_code unregister() override;
65 |
66 | private:
67 | ~TensorRTInferencer();
68 | std::unique_ptr m_logger;
69 | std::unique_ptr m_inferenceRuntime;
70 | size_t m_maxBatchSize;
71 | std::vector m_inputLayers;
72 | std::vector m_outputLayers;
73 | cudaStream_t m_cudaStream;
74 | nvinfer1::ICudaEngine* m_inferenceEngine;
75 | std::unique_ptr m_ownedInferenceEngine;
76 | std::unique_ptr m_inferenceContext;
77 | size_t m_ioTensorsCount;
78 | ModelMetaData m_modelInfo;
79 | bool m_hasImplicitBatch;
80 | std::vector m_modelEngineStream;
81 | size_t m_modelEngineStreamSize = 0;
82 |
83 | std::error_code ParseTRTModel();
84 | std::error_code getLayerInfo(LayerInfo& layer, std::string layerName);
85 | };
86 |
87 | } // namespace inferencer
88 | } // namespace cvcore
89 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TensorRTUtils.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include "gems/dnn_inferencer/inferencer/TensorRTUtils.h"
19 | #include
20 |
21 | namespace cvcore {
22 | namespace inferencer {
23 | using TensorLayout = cvcore::tensor_ops::TensorLayout;
24 | using ChannelType = cvcore::tensor_ops::ChannelType;
25 | using ChannelCount = cvcore::tensor_ops::ChannelCount;
26 | using ErrorCode = cvcore::tensor_ops::ErrorCode;
27 |
28 | std::error_code getCVCoreChannelTypeFromTensorRT(ChannelType& channelType,
29 | nvinfer1::DataType dtype) {
30 | if (dtype == nvinfer1::DataType::kINT8) {
31 | channelType = ChannelType::U8;
32 | } else if (dtype == nvinfer1::DataType::kHALF) {
33 | channelType = ChannelType::F16;
34 | } else if (dtype == nvinfer1::DataType::kFLOAT) {
35 | channelType = ChannelType::F32;
36 | } else {
37 | return ErrorCode::INVALID_OPERATION;
38 | }
39 |
40 | return ErrorCode::SUCCESS;
41 | }
42 |
43 | std::error_code getCVCoreChannelLayoutFromTensorRT(TensorLayout& channelLayout,
44 | nvinfer1::TensorFormat tensorFormat) {
45 | if (tensorFormat == nvinfer1::TensorFormat::kLINEAR) {
46 | channelLayout = TensorLayout::NCHW;
47 | } else if (tensorFormat == nvinfer1::TensorFormat::kHWC) {
48 | channelLayout = TensorLayout::HWC;
49 | } else {
50 | return ErrorCode::INVALID_OPERATION;
51 | }
52 |
53 | return ErrorCode::SUCCESS;
54 | }
55 |
56 | } // namespace inferencer
57 | } // namespace cvcore
58 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TensorRTUtils.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 | #pragma once
15 |
16 | #include "NvInferRuntime.h"
17 | #include "extensions/tensorops/core/Tensor.h"
18 | #include "Errors.h"
19 |
20 | namespace cvcore {
21 | namespace inferencer {
22 |
23 | /*
24 | * Maps tensorrt datatype to cvcore Channel type.
25 | * @param channelType cvcore channel type.
26 | * @param dtype tensorrt datatype
27 | * return error code
28 | */
29 | std::error_code getCVCoreChannelTypeFromTensorRT(
30 | cvcore::tensor_ops::ChannelType& channelType,
31 | nvinfer1::DataType dtype);
32 |
33 | /*
34 | * Maps tensorrt datatype to cvcore Channel type.
35 | * @param channelLayout cvcore channel type.
36 | * @param dtype tensorrt layout
37 | * return error code
38 | */
39 | std::error_code getCVCoreChannelLayoutFromTensorRT(
40 | cvcore::tensor_ops::TensorLayout& channelLayout,
41 | nvinfer1::TensorFormat tensorFormat);
42 |
43 | } // namespace inferencer
44 | } // namespace cvcore
45 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TritonGrpcInferencer.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 | #pragma once
15 | #ifdef ENABLE_TRITON
16 |
17 | #include
18 | #include
19 | #include
20 | #include
21 |
22 | #include "cv/inferencer/Errors.h"
23 | #include "cv/inferencer/IInferenceBackend.h"
24 | #include "cv/inferencer/Inferencer.h"
25 | #include "grpc_client.h"
26 |
27 | namespace cvcore {
28 | namespace inferencer {
29 | namespace tc = triton::client;
30 |
31 | class TritonGrpcInferencer : public IInferenceBackendClient {
32 | public:
33 | TritonGrpcInferencer(const TritonRemoteInferenceParams& params);
34 |
35 | // Set input layer tensor
36 | std::error_code setInput(const cvcore::TensorBase& trtInputBuffer,
37 | std::string inputLayerName) override;
38 | // Sets output layer tensor
39 | std::error_code setOutput(cvcore::TensorBase& trtOutputBuffer,
40 | std::string outputLayerName) override;
41 |
42 | // Get the model metadata parsed based on the model file
43 | // This would be done in initialize call itself. User can access the modelMetaData
44 | // created using this API.
45 | ModelMetaData getModelMetaData() const override;
46 |
47 | // Triton will use infer and TensorRT would use enqueueV2
48 | std::error_code infer(size_t batchSize = 1) override;
49 |
50 | // Applicable only for Native TRT
51 | std::error_code setCudaStream(cudaStream_t) override;
52 |
53 | // Unregister shared memory for layer
54 | std::error_code unregister(std::string layerName) override;
55 |
56 | // Unregister all shared memory
57 | std::error_code unregister() override;
58 |
59 | private:
60 | // Parse grpc model
61 | std::error_code ParseGrpcModel();
62 | std::unique_ptr client;
63 | ModelMetaData modelInfo;
64 | std::vector> inputRequests;
65 | std::vector> outputRequests;
66 | std::vector inputMap;
67 | std::vector inputMapHistory;
68 | std::vector outputMapHistory;
69 | std::vector outputMap;
70 | std::string modelVersion, modelName;
71 | };
72 |
73 | } // namespace inferencer
74 | } // namespace cvcore
75 | #endif
76 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TritonUtils.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #ifdef ENABLE_TRITON
18 |
19 | #include
20 | #include
21 |
22 | #include "gems/dnn_inferencer/inferencer/TritonUtils.h"
23 |
24 | namespace cvcore {
25 | namespace inferencer {
26 | using ChannelType = cvcore::tensor_ops::ChannelType;
27 | bool getCVCoreChannelType(ChannelType& channelType, std::string dtype) {
28 | if (dtype.compare("UINT8") == 0) {
29 | channelType = ChannelType::U8;
30 | } else if (dtype.compare("UINT16") == 0) {
31 | channelType = ChannelType::U16;
32 | } else if (dtype.compare("FP16") == 0) {
33 | channelType = ChannelType::F16;
34 | } else if (dtype.compare("FP32") == 0) {
35 | channelType = ChannelType::F32;
36 | } else if (dtype.compare("FP64") == 0) {
37 | channelType = ChannelType::F64;
38 | } else {
39 | return false;
40 | }
41 |
42 | return true;
43 | }
44 |
45 | bool getTritonChannelType(std::string& dtype, ChannelType channelType) {
46 | if (channelType == ChannelType::U8) {
47 | dtype = "UINT8";
48 | } else if (channelType == ChannelType::U16) {
49 | dtype = "UINT16";
50 | } else if (channelType == ChannelType::F16) {
51 | dtype = "FP16";
52 | } else if (channelType == ChannelType::F32) {
53 | dtype = "FP32";
54 | } else if (channelType == ChannelType::F64) {
55 | dtype = "FP64";
56 | } else {
57 | return false;
58 | }
59 |
60 | return true;
61 | }
62 |
63 | } // namespace inferencer
64 | } // namespace cvcore
65 | #endif
66 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/dnn_inferencer/inferencer/TritonUtils.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (c) 2021-2023, NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | *
4 | * NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
5 | * property and proprietary rights in and to this material, related
6 | * documentation and any modifications thereto. Any use, reproduction,
7 | * disclosure or distribution of this material and related documentation
8 | * without an express license agreement from NVIDIA CORPORATION or
9 | * its affiliates is strictly prohibited.
10 | *
11 | * SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES
12 | * SPDX-License-Identifier: LicenseRef-NvidiaProprietary
13 | */
14 |
15 | #pragma once
16 |
17 | #ifdef ENABLE_TRITON
18 | #include
19 |
20 | #include "grpc_client.h"
21 |
22 | #include "cv/core/Tensor.h"
23 | #include "cv/inferencer/Errors.h"
24 |
25 | namespace cvcore {
26 | namespace inferencer {
27 |
28 | /*
29 | * Maps triton datatype to cvcore Channel type.
30 | * @param channelType cvcore channel type.
31 | * @param dtype String representing triton datatype
32 | * return bool returns false if mapping was not successful.
33 | */
34 | bool getCVCoreChannelType(cvcore::ChannelType& channelType, std::string dtype);
35 |
36 | /*
37 | * Maps triton datatype to cvcore Channel type.
38 | * @param dtype String representing triton datatype
39 | * @param channelType cvcore channel type.
40 | * return bool returns false if mapping was not successful.
41 | */
42 | bool getTritonChannelType(std::string& dtype, cvcore::ChannelType channelType);
43 |
44 | } // namespace inferencer
45 | } // namespace cvcore
46 | #endif // ENABLE_TRITON
47 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/hash/hash_file.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 |
18 | #include
19 | #include // NOLINT(build/include_order)
20 |
21 | #include "common/fixed_vector.hpp"
22 | #include "common/span.hpp"
23 | #include "gems/gxf_helpers/expected_macro_gxf.hpp"
24 | #include "gems/hash/hash_file.hpp"
25 |
26 | namespace nvidia {
27 | namespace isaac {
28 |
29 | namespace {
30 |
31 | constexpr size_t kBlockSize = 8096;
32 |
33 | } // namespace
34 |
35 | // helper to get the hash of a file
36 | gxf::Expected hash_file(const char* path) {
37 | std::ifstream file;
38 | SHA256 hash;
39 | FixedVector buffer;
40 |
41 | size_t bytes_remaining = std::filesystem::file_size(path);
42 |
43 | file.open(path, std::ios_base::in | std::ios_base::binary);
44 |
45 | if (!file.good()) {
46 | return nvidia::gxf::Unexpected{GXF_FAILURE};
47 | }
48 |
49 | while (true) {
50 | size_t current_bytes = std::min(kBlockSize, bytes_remaining);
51 |
52 | file.read(reinterpret_cast(buffer.data()), current_bytes);
53 |
54 | if (!file.good()) {
55 | return nvidia::gxf::Unexpected{GXF_FAILURE};
56 | }
57 |
58 | RETURN_IF_ERROR(hash.hashData(Span(buffer.data(), current_bytes)));
59 |
60 | bytes_remaining -= current_bytes;
61 |
62 | if (bytes_remaining == 0) {
63 | RETURN_IF_ERROR(hash.finalize());
64 |
65 | return hash.toString();
66 | }
67 | }
68 | }
69 |
70 | } // namespace isaac
71 | } // namespace nvidia
72 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/hash/hash_file.hpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #pragma once
18 |
19 | #include "gems/hash/sha256.hpp"
20 |
21 | namespace nvidia {
22 | namespace isaac {
23 |
24 | // helper to get the hash of a file
25 | gxf::Expected hash_file(const char* path);
26 |
27 | } // namespace isaac
28 | } // namespace nvidia
29 |
--------------------------------------------------------------------------------
/gxf_isaac_bi3d/gxf/gems/hash/sha256.cpp:
--------------------------------------------------------------------------------
1 | // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2 | // Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
3 | //
4 | // Licensed under the Apache License, Version 2.0 (the "License");
5 | // you may not use this file except in compliance with the License.
6 | // You may obtain a copy of the License at
7 | //
8 | // http://www.apache.org/licenses/LICENSE-2.0
9 | //
10 | // Unless required by applicable law or agreed to in writing, software
11 | // distributed under the License is distributed on an "AS IS" BASIS,
12 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | // See the License for the specific language governing permissions and
14 | // limitations under the License.
15 | //
16 | // SPDX-License-Identifier: Apache-2.0
17 | #include "gems/hash/sha256.hpp"
18 |
19 | #include
20 |
21 | namespace nvidia {
22 | namespace isaac {
23 |
24 | namespace {
25 |
26 | constexpr uint32_t K[64] = { 0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5,
27 | 0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5,
28 | 0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3,
29 | 0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174,
30 | 0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc,
31 | 0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da,
32 | 0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7,
33 | 0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967,
34 | 0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13,
35 | 0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85,
36 | 0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3,
37 | 0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070,
38 | 0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5,
39 | 0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3,
40 | 0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208,
41 | 0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2 };
42 |
43 | #define DBL_INT_ADD(a, b, c) \
44 | if ((a) > 0xFFFFFFFF - (c)) { \
45 | ++(b); \
46 | } \
47 | (a) += (c);
48 |
49 | #define ROTLEFT(a, b) (((a) << (b)) | ((a) >> (32 - (b))))
50 | #define ROTRIGHT(a, b) (((a) >> (b)) | ((a) << (32 - (b))))
51 |
52 | #define CH(x, y, z) (((x) & (y)) ^ (~(x) & (z)))
53 | #define MAJ(x, y, z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z)))
54 |
55 | #define EP0(x) (ROTRIGHT((x), 2) ^ ROTRIGHT((x), 13) ^ ROTRIGHT((x), 22))
56 | #define EP1(x) (ROTRIGHT((x), 6) ^ ROTRIGHT((x), 11) ^ ROTRIGHT((x), 25))
57 | #define SIG0(x) (ROTRIGHT((x), 7) ^ ROTRIGHT((x), 18) ^ ((x) >> 3))
58 | #define SIG1(x) (ROTRIGHT((x), 17) ^ ROTRIGHT((x), 19) ^ ((x) >> 10))
59 |
60 | } // namespace
61 |
62 | gxf::Expected SHA256::Hash(const Span data) {
63 | SHA256 hasher;
64 | return hasher.hashData(data)
65 | .and_then([&]() { return hasher.finalize(); })
66 | .substitute(hasher.hash());
67 | }
68 |
69 | gxf::Expected SHA256::Hash(const Span data) {
70 | auto span = Span(reinterpret_cast(data.data()), data.size());
71 | return Hash(span).map(ToString);
72 | }
73 |
74 | void SHA256::Initialize(SHA256_CTX& ctx) {
75 | ctx.datalen = 0;
76 | ctx.bitlen[0] = 0;
77 | ctx.bitlen[1] = 0;
78 | ctx.state[0] = 0x6a09e667;
79 | ctx.state[1] = 0xbb67ae85;
80 | ctx.state[2] = 0x3c6ef372;
81 | ctx.state[3] = 0xa54ff53a;
82 | ctx.state[4] = 0x510e527f;
83 | ctx.state[5] = 0x9b05688c;
84 | ctx.state[6] = 0x1f83d9ab;
85 | ctx.state[7] = 0x5be0cd19;
86 | }
87 |
88 | gxf::Expected