diff --git a/.gitattributes b/.gitattributes
index 4ffde33..e699ac4 100644
--- a/.gitattributes
+++ b/.gitattributes
@@ -1,3 +1,6 @@
+# Ignore Python files in linguist
+*.py linguist-detectable=false
+
# Images
*.gif filter=lfs diff=lfs merge=lfs -text
*.jpg filter=lfs diff=lfs merge=lfs -text
diff --git a/README.md b/README.md
index e9be04e..6fdb01f 100644
--- a/README.md
+++ b/README.md
@@ -4,17 +4,19 @@
---
## Webinar Available
-Learn how to use this package by watching our on-demand webinar: [Using ML Models in ROS2 to Robustly Estimate Distance to Obstacles](https://gateway.on24.com/wcc/experience/elitenvidiabrill/1407606/3998202/isaac-ros-webinar-series)
+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)
---
## Overview
-This repository provides NVIDIA hardware-accelerated packages for proximity segmentation. The `isaac_ros_bi3d` package uses an optimized [Bi3D](https://arxiv.org/abs/2005.07274) model to perform stereo-depth estimation via binary classification, which is used for proximity segmentation. Proximity segmentation can be used to determine whether an obstacle is within a proximity field and to avoid collisions with obstacles during navigation.
+This repository provides NVIDIA hardware-accelerated packages for proximity segmentation. The `isaac_ros_bi3d` package uses the optimized [Bi3D DNN model](https://catalog.ngc.nvidia.com/orgs/nvidia/teams/isaac/models/bi3d_proximity_segmentation) to perform stereo-depth estimation via binary classification, which is used for proximity segmentation. Proximity segmentation can be used to determine whether an obstacle is within a proximity field and to avoid collisions with obstacles during navigation.
-Proximity segmentation predicts freespace from the ground plane, eliminating the need to perform ground plane removal from the segmentation image. The `isaac_ros_bi3d_freespace` package leverages this functionality to produce an occupancy grid that indicates freespace in the neighborhood of the robot. This camera-based solution offers a number of appealing advantages over traditional 360 lidar occupancy scanning, including better detection of low-profile obstacles.
+
-Compared to other stereo disparity functions, proximity segmentation is unique in that it provides a prediction of whether an obstacle is within a proximity field, instead of continuous depth, while simultaneously predicting freespace from the ground plane, which other functions typically do not provide. Proximity segmentation is diverse relative to other stereo disparity functions in Isaac ROS, as it is a different algorithm that runs on NVIDIA DLA (deep learning accelerator), which is separate and independent from the GPU. For more information on disparity, refer to [this page](https://en.wikipedia.org/wiki/Binocular_disparity).
+[Bi3D](https://arxiv.org/abs/2005.07274) is used in a graph of nodes to provide proximity segmentation from a time-synchronized input left and right stereo image pair. Images to Bi3D need to be rectified and resized to the appropriate input resolution. The aspect ratio of the image needs to be maintained; hence, a crop and resize may be required to maintain the input aspect ratio. The graph for DNN encode, to DNN inference, to DNN decode is part of the Bi3D node. Inference is performed using TensorRT, as the Bi3D DNN model is designed to use optimizations supported by TensorRT.
+
+Compared to other stereo disparity functions, proximity segmentation provides a prediction of whether an obstacle is within a proximity field, as opposed to continuous depth, while simultaneously predicting freespace from the ground plane, which other functions typically do not provide. Also unlike other stereo disparity functions in Isaac ROS, proximity segmentation runs on NVIDIA DLA (deep learning accelerator), which is separate and independent from the GPU. For more information on disparity, refer to [this page](https://en.wikipedia.org/wiki/Binocular_disparity).
### Isaac ROS NITROS Acceleration
@@ -22,15 +24,11 @@ This package is powered by [NVIDIA Isaac Transport for ROS (NITROS)](https://dev
## Performance
-The following are the benchmark performance results of the prepared pipelines in this package, by supported platform:
-
-| Pipeline | AGX Orin | Orin Nano | x86_64 w/ RTX 3060 Ti |
-| ----------------------------- | ------------------- | ---------------- | --------------------- |
-| Bi3D Stereo Node (576p) (DLA) | 62 fps
46ms | N/A | N/A |
-| Bi3D Stereo Node (576p) (GPU) | 81 fps
61ms | 25 fps
65ms | 145 fps
386ms |
-| Freespace Segmentation | 1145 fps
1.3ms | 725 fps
2ms | 1490 fps
0.3ms |
+The following table summarizes the per-platform performance statistics of sample graphs that use this package, with links included to the full benchmark output. These benchmark configurations are taken from the [Isaac ROS Benchmark](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark#list-of-isaac-ros-benchmarks) collection, based on the [`ros2_benchmark`](https://github.com/NVIDIA-ISAAC-ROS/ros2_benchmark) framework.
-These data have been collected per the methodology described [here](https://github.com/NVIDIA-ISAAC-ROS/.github/blob/main/profile/performance-summary.md#methodology).
+| Sample Graph | Input Size | AGX Orin | Orin NX | x86_64 w/ RTX 3060 Ti |
+| ---------------------------------------------------------------------------------------------------------------------------------------- | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------ |
+| [Proximity Segmentation Node](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/scripts//isaac_ros_bi3d_node.py) | 576p | [45.9 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-agx_orin.json)
32 ms | [26.3 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-orin_nx.json)
65 ms | [148 fps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark/blob/main/results/isaac_ros_bi3d_node-x86_64_rtx_3060Ti.json)
22 ms |
## Table of Contents
@@ -52,7 +50,7 @@ These data have been collected per the methodology described [here](https://gith
- [Download Pre-trained Models (.onnx) from NGC](#download-pre-trained-models-onnx-from-ngc)
- [Convert the Pre-trained Models (.onnx) to TensorRT Engine Plans](#convert-the-pre-trained-models-onnx-to-tensorrt-engine-plans)
- [Generating Engine Plans for Jetson](#generating-engine-plans-for-jetson)
- - [Generating Engine Plans for x86_64](#generating-engine-plans-for-x86_64)
+ - [Generating Engine Plans for x86\_64](#generating-engine-plans-for-x86_64)
- [Package Reference](#package-reference)
- [`isaac_ros_bi3d`](#isaac_ros_bi3d)
- [Bi3D Overview](#bi3d-overview)
@@ -61,11 +59,6 @@ These data have been collected per the methodology described [here](https://gith
- [ROS Parameters](#ros-parameters)
- [ROS Topics Subscribed](#ros-topics-subscribed)
- [ROS Topics Published](#ros-topics-published)
- - [`isaac_ros_bi3d_freespace`](#isaac_ros_bi3d_freespace)
- - [Usage](#usage-1)
- - [ROS Parameters](#ros-parameters-1)
- - [ROS Topics Subscribed](#ros-topics-subscribed-1)
- - [ROS Topics Published](#ros-topics-published-1)
- [Troubleshooting](#troubleshooting)
- [Isaac ROS Troubleshooting](#isaac-ros-troubleshooting)
- [DNN and Triton Troubleshooting](#dnn-and-triton-troubleshooting)
@@ -73,24 +66,24 @@ These data have been collected per the methodology described [here](https://gith
## Latest Update
-Update 2022-10-19: Add Freespace Segmentation functionality to produce occupancy grids from Bi3D's output
+Update 2023-04-05: Source available GXF extensions
## Supported Platforms
-This package is designed and tested to be compatible with ROS2 Humble running on [Jetson](https://developer.nvidia.com/embedded-computing) or an x86_64 system with an NVIDIA GPU.
+This package is designed and tested to be compatible with ROS 2 Humble running on [Jetson](https://developer.nvidia.com/embedded-computing) or an x86_64 system with an NVIDIA GPU.
-> **Note**: Versions of ROS2 earlier than Humble are **not** supported. This package depends on specific ROS2 implementation features that were only introduced beginning with the Humble release.
+> **Note**: Versions of ROS 2 earlier than Humble are **not** supported. This package depends on specific ROS 2 implementation features that were only introduced beginning with the Humble release.
-| Platform | Hardware | Software | Notes |
-| -------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| Jetson | [Jetson Orin](https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/jetson-orin/)
[Jetson Xavier](https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/jetson-agx-xavier/) | [JetPack 5.0.2](https://developer.nvidia.com/embedded/jetpack) | For best performance, ensure that the [power settings](https://docs.nvidia.com/jetson/archives/r34.1/DeveloperGuide/text/SD/PlatformPowerAndPerformance.html) are configured appropriately. |
-| x86_64 | NVIDIA GPU | [Ubuntu 20.04+](https://releases.ubuntu.com/20.04/)
[CUDA 11.6.1+](https://developer.nvidia.com/cuda-downloads) |
+| Platform | Hardware | Software | Notes |
+| -------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| Jetson | [Jetson Orin](https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/jetson-orin/)
[Jetson Xavier](https://www.nvidia.com/en-us/autonomous-machines/embedded-systems/jetson-agx-xavier/) | [JetPack 5.1.1](https://developer.nvidia.com/embedded/jetpack) | For best performance, ensure that the [power settings](https://docs.nvidia.com/jetson/archives/r34.1/DeveloperGuide/text/SD/PlatformPowerAndPerformance.html) are configured appropriately. |
+| x86_64 | NVIDIA GPU | [Ubuntu 20.04+](https://releases.ubuntu.com/20.04/)
[CUDA 11.8+](https://developer.nvidia.com/cuda-downloads) |
### Docker
To simplify development, we strongly recommend leveraging the Isaac ROS Dev Docker images by following [these steps](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/dev-env-setup.md). This will streamline your development environment setup with the correct versions of dependencies on both Jetson and x86_64 platforms.
-> **Note:** All Isaac ROS quick start guides, tutorials, and examples have been designed with the Isaac ROS Docker images as a prerequisite.
+> **Note**: All Isaac ROS quick start guides, tutorials, and examples have been designed with the Isaac ROS Docker images as a prerequisite.
## Quickstart
@@ -136,10 +129,10 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock
```bash
/usr/src/tensorrt/bin/trtexec --saveEngine=/tmp/models/bi3d/bi3dnet_featnet.plan \
--onnx=/tmp/models/bi3d/featnet.onnx \
- --int8 --useDLACore=0 &&
+ --int8 --useDLACore=0 --allowGPUFallback &&
/usr/src/tensorrt/bin/trtexec --saveEngine=/tmp/models/bi3d/bi3dnet_segnet.plan \
--onnx=/tmp/models/bi3d/segnet.onnx \
- --int8 --useDLACore=0
+ --int8 --useDLACore=0 --allowGPUFallback
```
If using x86_64:
@@ -151,7 +144,7 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock
--onnx=/tmp/models/bi3d/segnet.onnx --int8
```
- > **Note:** The engine plans generated using the x86_64 commands will also work on Jetson, but performance will be reduced.
+ > **Note**: The engine plans generated using the x86_64 commands will also work on Jetson, but performance will be reduced.
7. Build and source the workspace:
@@ -170,7 +163,7 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock
9. Run the launch file to spin up a demo of this package:
```bash
- ros2 launch isaac_ros_bi3d_freespace isaac_ros_bi3d_freespace.launch.py featnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_featnet.plan \
+ ros2 launch isaac_ros_bi3d isaac_ros_bi3d.launch.py featnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_featnet.plan \
segnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_segnet.plan \
max_disparity_values:=10
```
@@ -188,26 +181,29 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock
ros2 bag play --loop src/isaac_ros_proximity_segmentation/resources/rosbags/bi3dnode_rosbag
```
-12. Open a **third** terminal inside the Docker container:
+12. Open two **new** terminals inside the Docker container for visualization:
```bash
cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
- ./scripts/run_dev.sh
+ ./scripts/run_dev.sh && source install/setup.bash
```
-13. Visualize the occupancy grid in RViz.
+13. Visualize the output.
- Start RViz:
+ Start disparity visualizer:
```bash
- rviz2
+ ros2 run isaac_ros_bi3d isaac_ros_bi3d_visualizer.py --max_disparity_value 10
```
+ Start image visualizer:
- In the left pane, change **Fixed Frame** to `base_link`.
-
- In the left pane, click the **Add** button, then select **By topic** followed by **Map** to add the occupancy grid.
-
-
+ ```bash
+ ros2 run image_view image_view --ros-args -r image:=rgb_left
+ ```
+
+
+
+
## Next Steps
@@ -215,12 +211,10 @@ To simplify development, we strongly recommend leveraging the Isaac ROS Dev Dock
To continue your exploration, check out the following suggested examples:
-| Example | Dependencies |
-| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- |
-| [Zone detection for an autonomous mobile robot (AMR)](./docs/bi3d-example.md) | -- |
-| [Tutorial with RealSense, Bi3D, and Freespace Segmentation](./docs/tutorial-bi3d-freespace-realsense.md) | [`realsense-ros`](https://github.com/NVIDIA-ISAAC-ROS/.github/blob/main/profile/realsense-setup.md) |
-| [Tutorial for Bi3D with Isaac Sim](./docs/tutorial-bi3d-isaac-sim.md) | -- |
-| [Tutorial for Freespace Segmentation with Isaac Sim](./docs/tutorial-bi3d-freespace-isaac-sim.md) | -- |
+| Example | Dependencies |
+| ----------------------------------------------------------------------------- | ------------ |
+| [Zone detection for an autonomous mobile robot (AMR)](./docs/bi3d-example.md) | -- |
+| [Tutorial for Bi3D with Isaac Sim](./docs/tutorial-bi3d-isaac-sim.md) | -- |
### Use Different Models
@@ -255,12 +249,12 @@ The following steps show how to download pretrained Bi3D DNN inference models.
`trtexec` is used to convert pre-trained models (`.onnx`) to the TensorRT engine plan and is included in the Isaac ROS docker container under `/usr/src/tensorrt/bin/trtexec`.
-> **Tip:** Use `/usr/src/tensorrt/bin/trtexec -h` for more information on using the tool.
+> **Tip**: Use `/usr/src/tensorrt/bin/trtexec -h` for more information on using the tool.
#### Generating Engine Plans for Jetson
```bash
- /usr/src/tensorrt/bin/trtexec --onnx= --saveEngine= --useDLACore= --int8
+ /usr/src/tensorrt/bin/trtexec --onnx= --saveEngine= --useDLACore= --int8 --allowGPUFallback
```
#### Generating Engine Plans for x86_64
@@ -277,7 +271,7 @@ The following steps show how to download pretrained Bi3D DNN inference models.
Bi3D predicts if an obstacle is within a given proximity field via a series of binary classifications; the binary classification per pixel determines if the pixel is in front of or behind the proximity field. As such, Bi3D is differentiated from other stereo disparity functions which output continuous [disparity](https://en.wikipedia.org/wiki/Binocular_disparity). Bi3D allows you to increase the diversity of functions used for obstacle detection and improve hardware diversity because Isaac ROS Proximity Segmentation is optimized to run on NVIDIA DLA hardware, which is separate from the GPU. In the form presented here, Bi3D is intended to provide proximity detections, and is not a replacement for the continuous depth estimation provided by Isaac ROS DNN Stereo Disparity.
-> **Note:** This DNN is optimized for and evaluated with RGB global shutter camera images, and accuracy may vary on monochrome images.
+> **Note**: This DNN is optimized for and evaluated with RGB global shutter camera images, and accuracy may vary on monochrome images.
#### Usage
@@ -318,42 +312,7 @@ The prediction of freespace eliminates the need for ground plane removal in the
| ROS Topic | Interface | Description |
| --------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `bi3d_node/bi3d_output` | [stereo_msgs/DisparityImage](https://github.com/ros2/common_interfaces/blob/humble/stereo_msgs/msg/DisparityImage.msg) | The proximity segmentation of Bi3D given as a disparity image. For pixels not deemed freespace, their value is set to the closest (largest) disparity plane that is breached. A pixel value is set to 0 if it doesn't breach any disparity plane or if it is freespace.
Output Resolution: 960x576 (WxH) |
-| `bi3d_node/bi3d_disparity_values` | [isaac_ros_bi3d_interfaces/Bi3DInferenceParametersArray](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/isaac_ros_bi3d_interfaces/msg/Bi3DInferenceParametersArray.msg) | The disparity values used for Bi3D inference. The timestamp is matched to the timestamp in the correpsonding output image from `bi3d_node/bi3d_output` |
-
-### `isaac_ros_bi3d_freespace`
-
-#### Usage
-
-```bash
-ros2 launch isaac_ros_bi3d_freespace isaac_ros_freespace_segmentation.launch.py base_link_frame:=<"name of base link"> camera_frame:=<"name of camera frame"> s_x:=<"pixel pitch in x dimension"> s_y:=<"pixel pitch in y dimension"> f:=<"focal length"> grid_width:=<"desired grid width"> grid_height:=<"desired grid height"> grid_resolution:=<"desired grid resolution">
-```
-
-#### ROS Parameters
-
-| ROS Parameter | Type | Default | Description |
-| ----------------- | ------------- | ----------- | ------------------------------------------------------------------------------- |
-| `base_link_frame` | `std::string` | `base_link` | The name of the `tf2` frame attached to the robot base |
-| `camera_frame` | `std::string` | `camera` | The name of the `tf2` frame attached to the camera |
-| `s_x` | `double` | `1e5` | The pitch of pixels on the image sensor in the X dimension, in pixels per meter |
-| `s_y` | `double` | `1e5` | The pitch of pixels on the image sensor in the Y dimension, in pixels per meter |
-| `f` | `double` | `1e-2` | The focal length of the camera, in meters |
-| `grid_width` | `int` | `100` | The width of the output occupancy grid, in number of cells |
-| `grid_height` | `int` | `100` | The height of the output occupancy grid, in number of cells |
-| `grid_resolution` | `double` | `0.01` | The resolution of the output occupancy grid, in meters per cell |
-
-#### ROS Topics Subscribed
-
-| ROS Topic | Interface | Description |
-| -------------------------------- | ---------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- |
-| `freespace_segmentation/mask_in` | [stereo_msgs/DisparityImage](https://github.com/ros2/common_interfaces/blob/humble/stereo_msgs/msg/DisparityImage.msg) | The input disparity image, with pixels corresponding to ground labelled as 0 |
-
-> **Limitation:** For all input images, both the height and width must be an even number of pixels.
-
-#### ROS Topics Published
-
-| ROS Topic | Interface | Description |
-| --------------------------------------- | -------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------- |
-| `freespace_segmentation/occupancy_grid` | [nav_msgs/OccupancyGrid](https://github.com/ros2/common_interfaces/blob/humble/nav_msgs/msg/OccupancyGrid.msg) | The output occupancy grid, with cells marked as 0 if free |
+| `bi3d_node/bi3d_disparity_values` | [isaac_ros_bi3d_interfaces/Bi3DInferenceParametersArray](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/isaac_ros_bi3d_interfaces/msg/Bi3DInferenceParametersArray.msg) | The disparity values used for Bi3D inference. The timestamp is matched to the timestamp in the correpsonding output image from `bi3d_node/bi3d_output` |
## Troubleshooting
@@ -367,8 +326,8 @@ Check [here](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_dnn_inference/blob/ma
## Updates
-| Date | Changes |
-| ---------- | -------------------------------------------------------------------------------------- |
-| 2022-10-19 | Add Freespace Segmentation functionality to produce occupancy grids from Bi3D's output |
-| 2022-08-31 | Update to use latest model and to be compatible with JetPack 5.0.2 |
-| 2022-06-30 | Initial release |
+| Date | Changes |
+| ---------- | ------------------------------------------------------------------ |
+| 2023-04-05 | Source available GXF extensions |
+| 2022-08-31 | Update to use latest model and to be compatible with JetPack 5.0.2 |
+| 2022-06-30 | Initial release |
diff --git a/docs/tutorial-bi3d-freespace-isaac-sim.md b/docs/tutorial-bi3d-freespace-isaac-sim.md
deleted file mode 100644
index fb3cf5c..0000000
--- a/docs/tutorial-bi3d-freespace-isaac-sim.md
+++ /dev/null
@@ -1,46 +0,0 @@
-# Tutorial for Freespace Segmentation with Isaac Sim
-
-
-## Overview
-This tutorial demonstrates how to use a [Isaac Sim](https://developer.nvidia.com/isaac-sim) and [isaac_ros_bi3d_freespace](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_proximity_segmentation) to create a local occupancy grid.
-
-## Tutorial Walkthrough
-1. Complete steps 1-7 listed in the [Quickstart section](../README.md#quickstart) of the main README.
-2. Install and launch Isaac Sim following the steps in the [Isaac ROS Isaac Sim Setup Guide](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/isaac-sim-sil-setup.md)
-3. Open the Isaac ROS Common USD scene (using the **Content** window) located at:
-
- `omniverse://localhost/NVIDIA/Assets/Isaac/2022.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_apriltags_worker.usd`.
-
- And wait for it to load completely.
- > **Note:** To use a different server, replace `localhost` with ``
-4. Go to the **Stage** tab and select `/World/Carter_ROS/ROS_Cameras/ros2_create_camera_right_info`. In the **Property** tab, change the **Compute Node -> Inputs -> stereoOffset -> X** value from `0` to `-175.92`.
-
-5. Enable the right camera for a stereo image pair. Go to the **Stage** tab and select `/World/Carter_ROS/ROS_Cameras/enable_camera_right`, then tick the **Condition** checkbox.
-
-6. Project the `base_link` frame to the ground floor so that we can anchor our occupancy grid. Go to the **Stage** tab and select `/World/Carter_ROS/chassis_link/base_link`. In the **Property** tab, change the **Transform -> Translate -> Z** value from `0` to `-0.24`.
-
-
-7. Disable the clock reset when simulation is stopped. Go to the **Stage** tab and select `/World/Clock/isaac_read_simulation_time`, then untick the **Reset On Stop** checkbox.
-
-8. Press **Play** to start publishing data from the Isaac Sim application.
-
-9. Open a second terminal and attach to the container:
- ```bash
- cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
- ./scripts/run_dev.sh
- ```
-10. In the second terminal, start the `isaac_ros_bi3d` node using the launch files:
- ```bash
- ros2 launch isaac_ros_bi3d_freespace isaac_ros_bi3d_freespace_isaac_sim.launch.py \
- featnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_featnet.plan \
- segnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_segnet.plan \
- max_disparity_values:=32
- ```
- You should see a RViz window, as shown below:
-
-
-11. Optionally, you can run the visualizer script to visualize the disparity image.
- ```bash
- ros2 run isaac_ros_bi3d isaac_ros_bi3d_visualizer.py --disparity_topic bi3d_mask
- ```
-
diff --git a/docs/tutorial-bi3d-freespace-realsense.md b/docs/tutorial-bi3d-freespace-realsense.md
deleted file mode 100644
index e7473b0..0000000
--- a/docs/tutorial-bi3d-freespace-realsense.md
+++ /dev/null
@@ -1,77 +0,0 @@
-# Tutorial for Freespace Segmentation using a RealSense Camera
-
-
-
-## Overview
-
-This tutorial demonstrates how to use a [RealSense](https://www.intel.com/content/www/us/en/architecture-and-technology/realsense-overview.html) camera and [isaac_ros_bi3d_freespace](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_proximity_segmentation) to create a local occupancy grid.
-
-> Note: This tutorial has been tested with a RealSense D455/D435 connected to an x86 PC with an NVIDIA graphics card, as well as a Jetson Xavier AGX.
-
-## Tutorial Walkthrough
-
-1. Complete the [RealSense setup tutorial](https://github.com/NVIDIA-ISAAC-ROS/.github/blob/main/profile/realsense-setup.md).
-2. Complete steps 1-7 described in the [Quickstart Guide](../README.md#quickstart).
-3. Open a new terminal and launch the Docker container using the `run_dev.sh` script:
-
- ```bash
- cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
- ./scripts/run_dev.sh
- ```
-
-4. Build and source the workspace:
-
- ```bash
- cd /workspaces/isaac_ros-dev && \
- colcon build --symlink-install && \
- source install/setup.bash
- ```
-
-5. Please set your camera as shown in the image below, which is on a tripod ~10cm tall and parallel to the ground. Or you can change the static transform in launch file [here](../isaac_ros_bi3d_freespace/launch/isaac_ros_bi3d_freespace_realsense.launch.py#L144-157), according to the placement of your camera with respect to a occupancy grid origin frame.
-
-
-
-6. Run the launch file, which launches the example:
-
- ```bash
- ros2 launch isaac_ros_bi3d_freespace isaac_ros_bi3d_freespace_realsense.launch.py featnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_featnet.plan \
- segnet_engine_file_path:=/tmp/models/bi3d/bi3dnet_segnet.plan \
- max_disparity_values:=16
- ```
-
-7. Open a second terminal and attach to the container:
-
- ```bash
- cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
- ./scripts/run_dev.sh
- ```
-
-8. Optionally, you can run the visualizer script to visualize the disparity image.
-
- ```bash
- ros2 run isaac_ros_bi3d isaac_ros_bi3d_visualizer.py --disparity_topic bi3d_mask
- ```
-
-
-
-
- > Note: For more information on how to interpret the output, refer to the [interpreting the output section](../README.md#interpreting-the-output) of the main readme.
-
-9. Open a third terminal and attach to the container:
-
- ```bash
- cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \
- ./scripts/run_dev.sh
- ```
-
-10. Visualize the occupancy grid in RViz.
-
- Start RViz:
-
- ```bash
- rviz2
- ```
-
- In the left pane, change the **Fixed Frame** to `base_link`.
-
- In the left pane, click the **Add** button, then select **By topic** followed by **Map** to add the occupancy grid. You should see an ouput similar to the one shown at the top of this page.
diff --git a/docs/tutorial-bi3d-isaac-sim.md b/docs/tutorial-bi3d-isaac-sim.md
index d00b79d..90ddb65 100644
--- a/docs/tutorial-bi3d-isaac-sim.md
+++ b/docs/tutorial-bi3d-isaac-sim.md
@@ -1,28 +1,30 @@
# Tutorial for Bi3D with Isaac Sim
-
+
## Overview
-This tutorial walks through setting up a pipeline to [segment stereo image pairs](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_proximity_segmentation) generated by Isaac Sim by depth disparity levels. For more details on the output please refer to the [interpreting the output](../README.md#interpreting-the-output) section of the [main readme](../README.md).
+This tutorial walks through setting up a graph to [segment stereo image pairs](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_proximity_segmentation) generated by Isaac Sim by depth disparity levels. For more details on the output please refer to the [interpreting the output](../README.md#interpreting-the-output) section of the [main readme](../README.md).
+
+Last validated with [Isaac Sim 2022.2.1](https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/release_notes.html#id1)
## Tutorial Walkthrough
1. Complete steps 1-7 listed in the [Quickstart section](../README.md#quickstart) of the main README.
2. Install and launch Isaac Sim following the steps in the [Isaac ROS Isaac Sim Setup Guide](https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common/blob/main/docs/isaac-sim-sil-setup.md)
-3. Open the Isaac ROS Common USD scene (using the **Content** window) located at:
+3. Open the Isaac ROS Common USD scene (using the *Content* tab) located at:
- `omniverse://localhost/NVIDIA/Assets/Isaac/2022.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_apriltags_worker.usd`.
+ ```text
+ http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/2022.2.1/Isaac/Samples/ROS2/Scenario/carter_warehouse_apriltags_worker.usd
+ ```
And wait for it to load completely.
- > **Note:** To use a different server, replace `localhost` with ``
-4. Go to the **Stage** tab and select `/World/Carter_ROS/ROS_Cameras/ros2_create_camera_right_info`. In the **Property** tab, change the **Compute Node -> Inputs -> stereoOffset -> X** value from `0` to `-175.92`.
-
-
-5. Enable the right camera for a stereo image pair. Go to the **Stage** tab and select `/World/Carter_ROS/ROS_Cameras/enable_camera_right`, then tick the **Condition** checkbox.
-
+4. Go to the *Stage* tab and select `/World/Carter_ROS/ROS_Cameras/ros2_create_camera_right_info`, then in *Property* tab *-> OmniGraph Node -> Inputs -> stereoOffset X* change `0` to `-175.92`.
+
+5. Enable the right camera for a stereo image pair. Go to the *Stage* tab and select `/World/Carter_ROS/ROS_Cameras/enable_camera_right`, then tick the *Condition* checkbox.
+
6. Press **Play** to start publishing data from the Isaac Sim application.
-
+
7. Open a second terminal and attach to the container:
```bash
diff --git a/isaac_ros_bi3d/CMakeLists.txt b/isaac_ros_bi3d/CMakeLists.txt
index 867ca65..ee9bdfa 100644
--- a/isaac_ros_bi3d/CMakeLists.txt
+++ b/isaac_ros_bi3d/CMakeLists.txt
@@ -1,5 +1,5 @@
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
-# Copyright (c) 2022 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+# Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
@@ -15,51 +15,34 @@
#
# SPDX-License-Identifier: Apache-2.0
-cmake_minimum_required(VERSION 3.8)
-project(isaac_ros_bi3d)
-
-# Default to C++17
-if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif()
+cmake_minimum_required(VERSION 3.23.2)
+project(isaac_ros_bi3d LANGUAGES C CXX)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
-# Default to Release build
-if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "")
- set(CMAKE_BUILD_TYPE "Release" CACHE STRING "" FORCE)
-endif()
-
-message(STATUS "CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}")
-
-execute_process(COMMAND uname -m COMMAND tr -d '\n' OUTPUT_VARIABLE ARCHITECTURE)
-message(STATUS "Architecture: ${ARCHITECTURE}")
-
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()
-# bi3d_node
+# Bi3DNode
ament_auto_add_library(bi3d_node SHARED src/bi3d_node.cpp)
-target_compile_definitions(bi3d_node
- PRIVATE "COMPOSITION_BUILDING_DLL"
-)
rclcpp_components_register_nodes(bi3d_node "nvidia::isaac_ros::bi3d::Bi3DNode")
set(node_plugins "${node_plugins}nvidia::isaac_ros::bi3d::Bi3DNode;$\n")
-# Install config directory
-install(
- DIRECTORY config
- DESTINATION share/${PROJECT_NAME}
-)
+### Install extensions built from source
+
+# Bi3d
+add_subdirectory(gxf/bi3d)
+install(TARGETS gxf_cvcore_bi3d DESTINATION share/${PROJECT_NAME}/gxf/lib/bi3d)
+
+# Bi3d postprocessor
+add_subdirectory(gxf/bi3d_postprocessor)
+install(TARGETS gxf_bi3d_postprocessor DESTINATION share/${PROJECT_NAME}/gxf/lib/bi3d)
-set_target_properties(bi3d_node PROPERTIES BUILD_WITH_INSTALL_RPATH TRUE)
-install(TARGETS bi3d_node
- ARCHIVE DESTINATION lib
- LIBRARY DESTINATION lib
- RUNTIME DESTINATION bin
-)
+### End extensions
+
+install(PROGRAMS scripts/isaac_ros_bi3d_visualizer.py DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
@@ -69,9 +52,4 @@ if(BUILD_TESTING)
add_launch_test(test/isaac_ros_bi3d_test.py TIMEOUT "1000")
endif()
-install(PROGRAMS
- scripts/isaac_ros_bi3d_visualizer.py
- DESTINATION lib/${PROJECT_NAME}
-)
-
ament_auto_package(INSTALL_TO_SHARE launch config)
diff --git a/isaac_ros_bi3d/gxf/AMENT_IGNORE b/isaac_ros_bi3d/gxf/AMENT_IGNORE
new file mode 100644
index 0000000..e69de29
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/include/cv/bi3d/Bi3D.h b/isaac_ros_bi3d/gxf/bi3d/3dv/include/cv/bi3d/Bi3D.h
new file mode 100644
index 0000000..81671a9
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/include/cv/bi3d/Bi3D.h
@@ -0,0 +1,230 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef CVCORE_BI3D_H_
+#define CVCORE_BI3D_H_
+
+#include
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+
+namespace cvcore { namespace bi3d {
+
+enum class ProcessingControl : std::uint8_t
+{
+ DISABLE = 0,
+ ENABLE = 1
+};
+
+/**
+ * Interface for Loading and running inference on bi3d network.
+ */
+class Bi3D
+{
+ public:
+ using InferencerParams = inferencer::TensorRTInferenceParams;
+
+ /**
+ * Default Image Processing Params for Bi3D.
+ */
+ static const ImagePreProcessingParams defaultPreProcessorParams;
+
+ /**
+ * Default Model Input Params for Bi3D.
+ */
+ static const ModelInputParams defaultModelInputParams;
+
+ /**
+ * Default inference Params for Bi3D.
+ */
+ static const InferencerParams defaultFeatureParams;
+ static const InferencerParams defaultHRParams;
+ static const InferencerParams defaultRefinementParams;
+ static const InferencerParams defaultSegmentationParams;
+
+ /**
+ * Bi3D extra params
+ */
+ struct Bi3DParams
+ {
+ std::size_t maxDisparityLevels; // Maximum pixel-wise shift between left and right images
+ ProcessingControl edgeRefinement; // Switch to turn on/off edge refinement models (FeatNetHR and
+ // RefineNet) in inferencing
+ ProcessingControl sigmoidPostProcessing; // Switch to turn on/off sigmoid operation in postprocessing
+ ProcessingControl thresholdPostProcessing; // Switch to turn on/off thresholding in postprocessing
+ float thresholdValueLow; // The low value set by threshold postprocessing
+ float thresholdValueHigh; // The high value set by threshold postprocessing
+ float threshold; // The threshold value that casts pixel values to either low or high
+ };
+ static const Bi3DParams defaultBi3DParams;
+
+ /**
+ * Defaule Constructor of Bi3D.
+ */
+ Bi3D() = delete;
+
+ /**
+ * Constructor of Bi3D.
+ * @param params custom params for the network.
+ */
+ Bi3D(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ const InferencerParams & featureParams,
+ const InferencerParams & hrParams,
+ const InferencerParams & refinementParams,
+ const InferencerParams & segmentationParams,
+ const Bi3DParams & bi3dParams,
+ cudaStream_t stream = 0);
+
+ /**
+ * Destructor of Bi3D.
+ */
+ ~Bi3D();
+
+ /**
+ * Main interface to run inference.
+ * @param quantizedDisparity depth segmentation for input left and right images
+ * @param leftImage left image tensor in RGB HWC format.
+ * @param rightImage right image tensor in RGB HWC format.
+ * @param disparityLevels diparity value to run depth estimation based on.
+ */
+ void execute(Tensor & quantizedDisparity,
+ const Tensor & leftImage,
+ const Tensor & rightImage,
+ const Array & disparityLevels,
+ cudaStream_t stream = 0);
+
+ /**
+ * Main interface to run inference.
+ * @param disparityConfidence depth segmentation for input left and right images
+ * @param leftImage left image tensor in RGB HWC format.
+ * @param rightImage right image tensor in RGB HWC format.
+ * @param disparityLevels diparity value to run depth estimation based on.
+ */
+ void execute(Tensor & disparityConfidence,
+ const Tensor & leftImage,
+ const Tensor & rightImage,
+ const Array & disparityLevels,
+ cudaStream_t stream = 0);
+
+ /**
+ * Main interface to run inference.
+ * @param disparityConfidence depth segmentation for input left and right images
+ * @param leftImage left image tensor in RGB CHW format.
+ * @param rightImage right image tensor in RGB CHW format.
+ * @param disparityLevels diparity value to run depth estimation based on.
+ */
+ void execute(Tensor & disparityConfidence,
+ const Tensor & leftImage,
+ const Tensor & rightImage,
+ const Array & disparityLevels,
+ cudaStream_t stream = 0);
+
+ private:
+ struct Bi3DImpl;
+
+ std::unique_ptr m_pImpl;
+};
+
+/**
+ * Interface for running pre-processing for Bi3D.
+ */
+class Bi3DPreProcessor
+{
+ public:
+ /**
+ * Removing the default constructor for Bi3DPreProcessor.
+ */
+ Bi3DPreProcessor() = delete;
+
+ /**
+ * Constructor for Bi3DPreProcessor.
+ * @param preProcessorParams Image preprocessing parameters.
+ * @param modelInputParams Model input parameters.
+ */
+ Bi3DPreProcessor(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ cudaStream_t stream = 0);
+
+ /**
+ * Destructor for Bi3DPreProcessor.
+ */
+ ~Bi3DPreProcessor();
+
+ void execute(Tensor & preprocessedLeftImage,
+ Tensor & preprocessedRightImage,
+ const Tensor & leftImage,
+ const Tensor & rightImage,
+ cudaStream_t stream = 0);
+
+ void execute(Tensor & preprocessedLeftImage,
+ Tensor & preprocessedRightImage,
+ const Tensor & leftImage,
+ const Tensor & rightImage,
+ cudaStream_t stream = 0);
+
+ private:
+ struct Bi3DPreProcessorImpl;
+
+ std::unique_ptr m_pImpl;
+};
+
+/**
+ * Interface for running post-processing for Bi3D.
+ */
+class Bi3DPostProcessor
+{
+ public:
+ /**
+ * Removing the default constructor for Bi3DPostProcessor.
+ */
+ Bi3DPostProcessor() = delete;
+
+ /**
+ * Constructor for Bi3DPostProcessor.
+ * @param modelInputParams Model input parameters.
+ * @param bi3dParams Model parameters unique to this model.
+ */
+ Bi3DPostProcessor(const ModelInputParams & modelInputParams,
+ const Bi3D::Bi3DParams & bi3dParams,
+ cudaStream_t stream = 0);
+
+ /**
+ * Destructor for Bi3DPostProcessor.
+ */
+ ~Bi3DPostProcessor();
+
+ void execute(Tensor & disparityConfidence,
+ Tensor & rawDisparityConfidence,
+ cudaStream_t stream = 0);
+
+ private:
+ struct Bi3DPostProcessorImpl;
+
+ std::unique_ptr m_pImpl;
+};
+
+}} // namespace cvcore::bi3d
+
+#endif // CVCORE_BI3D_H_
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D.cpp b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D.cpp
new file mode 100644
index 0000000..096ede1
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D.cpp
@@ -0,0 +1,645 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include
+
+#include "Bi3D_detail.h"
+
+#include
+#include
+#include
+#include
+
+#include
+
+#ifdef NVBENCH_ENABLE
+#include
+#include
+#endif
+
+#include
+
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+
+#ifndef ENGINE_DIR
+#define ENGINE_DIR "models"
+#endif // ENGINE_DIR
+
+namespace cvcore { namespace bi3d {
+
+// =============================================================================
+// Model Parameters
+// =============================================================================
+
+const ImagePreProcessingParams Bi3D::defaultPreProcessorParams =
+{
+ BGR_U8, /**< Input Image Type. */
+ {1.0/127.5, 1.0/127.5, 1.0/127.5}, /**< Image Mean value per channel (OFFSET). */
+ {0.00392156862,
+ 0.00392156862,
+ 0.00392156862}, /**< Normalization values per channel (SCALE). */
+ {-127.5, -127.5, -127.5} /**< Standard deviation values per channel. */
+};
+
+const ModelInputParams Bi3D::defaultModelInputParams =
+{
+ 32, /**< Max Batch Size */
+ 960, /**< Width of the model input */
+ 576, /**< Height of the model input */
+ RGB_U8 /**< Format of the model input */
+};
+
+const Bi3D::InferencerParams Bi3D::defaultFeatureParams =
+{
+ inferencer::TRTInferenceType::TRT_ENGINE,
+ nullptr,
+ ENGINE_DIR "/bi3dnet_featnet.engine",
+ 1,
+ {{"input.1"}},
+ {{"97"}}
+};
+
+const Bi3D::InferencerParams Bi3D::defaultHRParams =
+{
+ inferencer::TRTInferenceType::TRT_ENGINE,
+ nullptr,
+ ENGINE_DIR "/bi3dnet_featnethr.engine",
+ 1,
+ {{"input.1"}},
+ {{"10"}}
+};
+
+const Bi3D::InferencerParams Bi3D::defaultRefinementParams =
+{
+ inferencer::TRTInferenceType::TRT_ENGINE,
+ nullptr,
+ ENGINE_DIR "/bi3dnet_refinenet.engine",
+ 1,
+ {{"input.1"}},
+ {{"6"}}
+};
+
+const Bi3D::InferencerParams Bi3D::defaultSegmentationParams =
+{
+ inferencer::TRTInferenceType::TRT_ENGINE,
+ nullptr,
+ ENGINE_DIR "/bi3dnet_segnet.engine",
+ 1,
+ {{"input.1"}},
+ {{"278"}}
+};
+
+const Bi3D::Bi3DParams Bi3D::defaultBi3DParams =
+{
+ 192/3,
+ ProcessingControl::DISABLE,
+ ProcessingControl::DISABLE,
+ ProcessingControl::ENABLE,
+ 0.0f,
+ 1.0f,
+ 0.5f
+};
+
+// =============================================================================
+// Bi3D Inferencer(s)
+// =============================================================================
+
+template
+class UnaryInferencer
+{
+ using InferencerFactory = inferencer::InferenceBackendFactory;
+
+ public:
+ UnaryInferencer() = delete;
+
+ UnaryInferencer(const std::string & name,
+ const Bi3D::InferencerParams & modelParams,
+ cudaStream_t stream = 0)
+ : m_name{name}, m_inferencer{nullptr}, m_modelParams{modelParams},
+ m_inferencerState{ErrorCode::SUCCESS}
+ {
+ this->resetInferencerState();
+ }
+
+ ~UnaryInferencer()
+ {
+ InferencerFactory::DestroyTensorRTInferenceBackendClient(m_inferencer);
+ }
+
+ std::error_code getInferencerState() const
+ {
+ return m_inferencerState;
+ }
+
+ std::error_code resetInferencerState()
+ {
+ if(m_inferencer)
+ {
+ m_inferencerState = InferencerFactory::DestroyTensorRTInferenceBackendClient(m_inferencer);
+ }
+
+ if(!m_inferencerState)
+ {
+ m_inferencerState = InferencerFactory::CreateTensorRTInferenceBackendClient(m_inferencer,
+ m_modelParams);
+ }
+
+ if(!m_inferencerState)
+ {
+ m_modelMeta = m_inferencer->getModelMetaData();
+ }
+
+ return m_inferencerState;
+ }
+
+ inferencer::LayerInfo getInputInfo() const
+ {
+ return m_modelMeta.inputLayers.at(m_modelParams.inputLayerNames[0]);
+ }
+
+ inferencer::LayerInfo getOutputInfo() const
+ {
+ return m_modelMeta.outputLayers.at(m_modelParams.outputLayerNames[0]);
+ }
+
+ std::error_code execute(OutputTensorType & response,
+ const InputTensorType & signal,
+ cudaStream_t stream = 0)
+ {
+#ifdef NVBENCH_ENABLE
+ const std::string testName = m_name + "_batch" +
+ std::to_string(m_modelParams.maxBatchSize) + "_" +
+ std::to_string(signal.getWidth()) + "x" +
+ std::to_string(signal.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ if(!m_inferencerState)
+ {
+ m_inferencerState = m_inferencer->setCudaStream(stream);
+ }
+
+ // Assigning the network buffers.
+ if(!m_inferencerState)
+ {
+ m_inferencerState = m_inferencer->setInput(dynamic_cast(signal),
+ m_modelParams.inputLayerNames[0]);
+ }
+ if(!m_inferencerState)
+ {
+ m_inferencerState = m_inferencer->setOutput(dynamic_cast(response),
+ m_modelParams.outputLayerNames[0]);
+ }
+
+ // Run the inference
+ if(!m_inferencerState)
+ {
+ m_inferencerState = m_inferencer->infer();
+ }
+
+ return m_inferencerState;
+ }
+
+ private:
+ inferencer::InferenceBackendClient m_inferencer;
+
+ std::string m_name;
+ Bi3D::InferencerParams m_modelParams;
+ inferencer::ModelMetaData m_modelMeta;
+ std::error_code m_inferencerState;
+};
+
+using FeatureExtractor = UnaryInferencer;
+using DisparityDetector = UnaryInferencer;
+using DisparityClassifier = UnaryInferencer;
+
+// =============================================================================
+// Bi3D Data Exchange
+// =============================================================================
+
+struct Bi3D::Bi3DImpl
+{
+ // Memory buffers
+ // NOTE: declared mutable because the data in these buffers must always change
+ mutable detail::PreprocessedImage m_preprocessedLeftImageDevice;
+ mutable detail::PreprocessedImage m_preprocessedRightImageDevice;
+ mutable detail::FeatureResponse m_leftFeaturesDevice;
+ mutable detail::FeatureResponse m_rightFeaturesDevice;
+ mutable detail::FeatureResponse m_hrFeaturesDevice;
+ mutable detail::FeatureResponse m_leftFeaturesPadDevice;
+ mutable detail::FeatureResponse m_rightFeaturesPadDevice;
+ mutable detail::FeatureResponse m_mergedFeaturesDevice;
+ mutable detail::ConfidenceMap m_confidenceMapDevice;
+ mutable detail::ConfidenceMap m_confidenceMapResizeDevice;
+ mutable detail::GuidedConfidence m_fusedDisparityDevice;
+ mutable detail::DisparityConfidence m_disparityConfidenceDevice;
+
+ // Exchange buffers
+ mutable detail::QuantizedDisparity m_quantizedDisparityDevice;
+ mutable detail::DisparityConfidence m_disparityConfidenceExchangeDevice;
+
+ Bi3DParams m_bi3dParams;
+
+ // Processor(s)
+ std::unique_ptr m_preprocess;
+ std::unique_ptr m_featureInfer;
+ std::unique_ptr m_hrInfer;
+ std::unique_ptr m_segmentationInfer;
+ std::unique_ptr m_refinementInfer;
+ std::unique_ptr m_postprocess;
+
+ Bi3DImpl(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ const InferencerParams & featureParams,
+ const InferencerParams & hrParams,
+ const InferencerParams & refinementParams,
+ const InferencerParams & segmentationParams,
+ const Bi3DParams & bi3dParams,
+ cudaStream_t stream)
+ : m_preprocess{new Bi3DPreProcessor{preProcessorParams, modelInputParams, stream}},
+ m_featureInfer{new FeatureExtractor{"FeatureNetInferencer", featureParams, stream}},
+ m_segmentationInfer{new DisparityDetector{"SegmentationNetInferencer", segmentationParams, stream}},
+ m_postprocess{new Bi3DPostProcessor{modelInputParams, bi3dParams, stream}},
+ m_bi3dParams{bi3dParams}
+ {
+ // Configuring the preprocessor outputs
+ m_preprocessedLeftImageDevice = {m_featureInfer->getInputInfo().shape[3],
+ m_featureInfer->getInputInfo().shape[2],
+ false};
+ m_preprocessedRightImageDevice = {m_featureInfer->getInputInfo().shape[3],
+ m_featureInfer->getInputInfo().shape[2],
+ m_preprocessedLeftImageDevice.isCPU()};
+
+ // Output SegRefine: Accumulated confidence output at all disparity levels
+ m_disparityConfidenceDevice = {m_featureInfer->getInputInfo().shape[3],
+ m_featureInfer->getInputInfo().shape[2],
+ bi3dParams.maxDisparityLevels,
+ m_preprocessedLeftImageDevice.isCPU()};
+
+ // The output FeatureHRNet is concatinated together with the resized
+ // output of SegNet to form a guidance map as input into RefineNet
+ if(m_bi3dParams.edgeRefinement == ProcessingControl::ENABLE)
+ {
+ // Load featnethr and refinenet only necessary
+ m_hrInfer.reset(new FeatureExtractor{"FeatureHRNetInferencer", hrParams, stream});
+ m_refinementInfer.reset(new DisparityClassifier{"RefinementNetInferencer", refinementParams, stream});
+ m_fusedDisparityDevice = {m_refinementInfer->getInputInfo().shape[3],
+ m_refinementInfer->getInputInfo().shape[2],
+ m_refinementInfer->getInputInfo().shape[1],
+ m_preprocessedLeftImageDevice.isCPU()};
+ m_confidenceMapResizeDevice = {m_refinementInfer->getInputInfo().shape[3],
+ m_refinementInfer->getInputInfo().shape[2],
+ m_fusedDisparityDevice.getData()
+ + 0*m_fusedDisparityDevice.getStride(TensorDimension::CHANNEL),
+ m_preprocessedLeftImageDevice.isCPU()};
+ m_hrFeaturesDevice = {m_hrInfer->getOutputInfo().shape[3],
+ m_hrInfer->getOutputInfo().shape[2],
+ m_hrInfer->getOutputInfo().shape[1],
+ m_fusedDisparityDevice.getData()
+ + 1*m_fusedDisparityDevice.getStride(TensorDimension::CHANNEL),
+ m_preprocessedLeftImageDevice.isCPU()};
+ }
+
+ // Output SegNet: Computed disparity confidence at a given disparity level
+ m_confidenceMapDevice = {m_segmentationInfer->getOutputInfo().shape[3],
+ m_segmentationInfer->getOutputInfo().shape[2],
+ m_preprocessedLeftImageDevice.isCPU()};
+
+ // Input SegNet: The concatinated left and right extracted image
+ // features from FeatureNet
+ m_mergedFeaturesDevice = {m_segmentationInfer->getInputInfo().shape[3],
+ m_segmentationInfer->getInputInfo().shape[2],
+ m_segmentationInfer->getInputInfo().shape[1],
+ m_preprocessedLeftImageDevice.isCPU()};
+
+ // The output extracted right features of FetureNet are padded and shifted
+ // horizontally by the given disparity level. The left features are zero
+ // padded to the same size as the right features.
+ // NOTE: This model assumes the left and right image are horizontally
+ // aligned. That is, the transformation from camera left to camera
+ // right is strictly along the horizontal axis relative to lab frame.
+ m_leftFeaturesPadDevice = {m_segmentationInfer->getInputInfo().shape[3],
+ m_featureInfer->getOutputInfo().shape[2],
+ m_featureInfer->getOutputInfo().shape[1],
+ m_mergedFeaturesDevice.getData()
+ + 0*m_mergedFeaturesDevice.getStride(TensorDimension::CHANNEL),
+ m_preprocessedLeftImageDevice.isCPU()};
+ m_rightFeaturesPadDevice = {m_segmentationInfer->getInputInfo().shape[3],
+ m_featureInfer->getOutputInfo().shape[2],
+ m_featureInfer->getOutputInfo().shape[1],
+ m_mergedFeaturesDevice.getData()
+ + m_featureInfer->getOutputInfo().shape[1]
+ * m_mergedFeaturesDevice.getStride(TensorDimension::CHANNEL),
+ m_preprocessedLeftImageDevice.isCPU()};
+
+ // Output FeatureNet: Feature extraction on the left and right images respectively
+ m_leftFeaturesDevice = {m_featureInfer->getOutputInfo().shape[3],
+ m_featureInfer->getOutputInfo().shape[2],
+ m_featureInfer->getOutputInfo().shape[1],
+ m_preprocessedLeftImageDevice.isCPU()};
+ m_rightFeaturesDevice = {m_featureInfer->getOutputInfo().shape[3],
+ m_featureInfer->getOutputInfo().shape[2],
+ m_featureInfer->getOutputInfo().shape[1],
+ m_preprocessedLeftImageDevice.isCPU()};
+ }
+
+ void resizeBuffers(std::size_t width, std::size_t height)
+ {
+ if(m_quantizedDisparityDevice.getDimCount() > 0 &&
+ m_quantizedDisparityDevice.getWidth() == width &&
+ m_quantizedDisparityDevice.getHeight() == height)
+ {
+ return;
+ }
+
+ m_disparityConfidenceExchangeDevice = {width, height,
+ m_disparityConfidenceDevice.getChannelCount(),
+ m_preprocessedLeftImageDevice.isCPU()};
+ m_quantizedDisparityDevice = {width, height,
+ m_disparityConfidenceDevice.getChannelCount(),
+ m_preprocessedLeftImageDevice.isCPU()};
+ }
+};
+
+// =============================================================================
+// Bi3D Frontend
+// =============================================================================
+
+Bi3D::Bi3D(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ const InferencerParams & featureParams,
+ const InferencerParams & hrParams,
+ const InferencerParams & refinementParams,
+ const InferencerParams & segmentationParams,
+ const Bi3DParams & bi3dParams,
+ cudaStream_t stream)
+ : m_pImpl{new Bi3DImpl{preProcessorParams, modelInputParams, featureParams,
+ hrParams, refinementParams, segmentationParams,
+ bi3dParams, stream}} {}
+
+Bi3D::~Bi3D() {}
+
+void Bi3D::execute(detail::DisparityConfidence & disparityConfidence,
+ const detail::PreprocessedImage & leftImage,
+ const detail::PreprocessedImage & rightImage,
+ const detail::DisparityLevels & disparityLevels,
+ cudaStream_t stream)
+{
+#ifdef NVBENCH_ENABLE
+ const std::string testName = "Bi3DF32_batch" +
+ std::to_string(1) + "_" +
+ std::to_string(leftImage.getWidth()) + "x" +
+ std::to_string(leftImage.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ if(disparityConfidence.isCPU())
+ {
+ throw std::invalid_argument("cvcore::bi3d::Bi3D::execute ==> disparityConfidence "
+ "was allocated on host (CPU) and not device (GPU)");
+ }
+
+ if(leftImage.isCPU() || rightImage.isCPU())
+ {
+ throw std::invalid_argument("cvcore::bi3d::Bi3D::execute ==> leftImage or rightImage "
+ "was allocated on host (CPU) and not device (GPU)");
+ }
+
+ if(leftImage.getChannelCount() != rightImage.getChannelCount())
+ {
+ throw std::invalid_argument("cvcore::bi3d::Bi3D::execute ==> "
+ "leftImage and rightImage have incompatable channel "
+ "sizes inconsistent with model configuration parameters");
+ }
+
+ if(leftImage.getWidth() != rightImage.getWidth() ||
+ leftImage.getHeight() != rightImage.getHeight())
+ {
+ throw std::invalid_argument("cvcore::bi3d::Bi3D::execute ==> "
+ "leftImage and rightImage have incompatable width and height sizes inconsistent with model configuration parameters");
+ }
+
+ // This is a boolean flag to indicate execution of the post processing step in the case that:
+ // 1) One of the post processing types is enabled (either Sigmoid or Thresholding)
+ // 2) The input size is greater than the output size of SegNet
+ bool runPostProcessing = m_pImpl->m_bi3dParams.sigmoidPostProcessing == ProcessingControl::ENABLE ||
+ m_pImpl->m_bi3dParams.thresholdPostProcessing == ProcessingControl::ENABLE ||
+ disparityConfidence.getDataSize() > m_pImpl->m_disparityConfidenceDevice.getDataSize();
+
+ if(leftImage.getWidth() != m_pImpl->m_preprocessedLeftImageDevice.getWidth() ||
+ leftImage.getHeight() != m_pImpl->m_preprocessedLeftImageDevice.getHeight())
+ {
+ // Running the preprocessing
+ m_pImpl->m_preprocess->execute(m_pImpl->m_preprocessedLeftImageDevice,
+ m_pImpl->m_preprocessedRightImageDevice,
+ leftImage, rightImage, stream);
+
+ // Running feature extraction
+ m_pImpl->m_featureInfer->execute(m_pImpl->m_leftFeaturesDevice,
+ m_pImpl->m_preprocessedLeftImageDevice,
+ stream);
+ m_pImpl->m_featureInfer->execute(m_pImpl->m_rightFeaturesDevice,
+ m_pImpl->m_preprocessedRightImageDevice,
+ stream);
+ }
+ else
+ {
+ // Running feature extraction
+ m_pImpl->m_featureInfer->execute(m_pImpl->m_leftFeaturesDevice,
+ leftImage, stream);
+ m_pImpl->m_featureInfer->execute(m_pImpl->m_rightFeaturesDevice,
+ rightImage, stream);
+ }
+
+ if(m_pImpl->m_bi3dParams.edgeRefinement == ProcessingControl::ENABLE)
+ {
+ m_pImpl->m_hrInfer->execute(m_pImpl->m_hrFeaturesDevice,
+ m_pImpl->m_preprocessedLeftImageDevice,
+ stream);
+ }
+
+ // Moving the left image extracted features to a larger buffer for maximal
+ // disparity calculation
+ detail::Pad(m_pImpl->m_leftFeaturesPadDevice, m_pImpl->m_leftFeaturesDevice,
+ 0, 0, stream);
+
+#ifdef NVBENCH_ENABLE
+ {
+ const std::string testName = "DisparityInferenceLoop_loop" +
+ std::to_string(disparityLevels.getSize()) + "_" +
+ std::to_string(leftImage.getWidth()) + "x" +
+ std::to_string(leftImage.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+ for(std::size_t i = 0; i < disparityLevels.getSize(); ++i)
+ {
+ // Padding the right image extracted features to the designated disparity
+ // level
+ detail::Pad(m_pImpl->m_rightFeaturesPadDevice, m_pImpl->m_rightFeaturesDevice,
+ 0, disparityLevels[i], stream);
+
+ // Extracted features are passively concatenated into m_mergedFeaturesDevice
+ // See: Bi3D::Bi3DImpl::Bi3DImpl()
+
+ // Computing the depth confidence map on the given disparity level
+ m_pImpl->m_segmentationInfer->execute(m_pImpl->m_confidenceMapDevice,
+ m_pImpl->m_mergedFeaturesDevice,
+ stream);
+
+ // In the case where edge refinement is DISABLED and no postprocessing
+ // is needed, the output buffer to Bi3D is directly used for computing
+ // the disparity confidence. `m_pImpl->m_confidenceMapResizeDevice` is
+ // a memory overlay of either the Bi3D output buffer `disparityConfidence`
+ // or the swap buffer `m_pImpl->m_disparityConfidenceDevice` which reflects
+ // the output format of SegNet. If no postprocessing is needed
+ // `disparityConfidence` is directly used, else the swap buffer
+ // `m_pImpl->m_disparityConfidenceDevice` is used to compute the
+ // first pass dispairty confidence before post processing.
+ // Cropping and resizing the disparity confidence to refinement size
+ if(m_pImpl->m_bi3dParams.edgeRefinement == ProcessingControl::DISABLE)
+ {
+ if(!runPostProcessing)
+ {
+ m_pImpl->m_confidenceMapResizeDevice = {
+ disparityConfidence.getWidth(),
+ disparityConfidence.getHeight(),
+ disparityConfidence.getData()
+ + i*disparityConfidence.getStride(TensorDimension::CHANNEL),
+ disparityConfidence.isCPU()};
+ }
+ else
+ {
+ m_pImpl->m_confidenceMapResizeDevice = {
+ m_pImpl->m_disparityConfidenceDevice.getWidth(),
+ m_pImpl->m_disparityConfidenceDevice.getHeight(),
+ m_pImpl->m_disparityConfidenceDevice.getData()
+ + i*m_pImpl->m_disparityConfidenceDevice.getStride(TensorDimension::CHANNEL),
+ m_pImpl->m_disparityConfidenceDevice.isCPU()};
+ }
+ }
+ detail::CropAndResize(m_pImpl->m_confidenceMapResizeDevice,
+ m_pImpl->m_confidenceMapDevice,
+ {0, 0,
+ static_cast(m_pImpl->m_confidenceMapResizeDevice.getWidth()),
+ static_cast(m_pImpl->m_confidenceMapResizeDevice.getHeight())},
+ {0, 0,
+ static_cast(m_pImpl->m_confidenceMapDevice.getWidth() - m_pImpl->m_bi3dParams.maxDisparityLevels),
+ static_cast(m_pImpl->m_confidenceMapDevice.getHeight())},
+ tensor_ops::INTERP_LINEAR, stream);
+
+ // The confidence map and the HR features are passively concatenated into
+ // m_fusedDisparityDevice
+ // See: Bi3D::Bi3DImpl::Bi3DImpl()
+
+ if(m_pImpl->m_bi3dParams.edgeRefinement == ProcessingControl::ENABLE)
+ {
+ // Creating an overlay of the memory sector to store the confidence results
+ // channel-wise
+ detail::RefinedConfidence refinedConfidenceDevice{
+ m_pImpl->m_disparityConfidenceDevice.getWidth(),
+ m_pImpl->m_disparityConfidenceDevice.getHeight(),
+ m_pImpl->m_disparityConfidenceDevice.getData()
+ + i*m_pImpl->m_disparityConfidenceDevice.getStride(TensorDimension::CHANNEL),
+ m_pImpl->m_disparityConfidenceDevice.isCPU()};
+ detail::Clear(refinedConfidenceDevice, stream);
+
+ // Computing the refined confidence
+ m_pImpl->m_refinementInfer->execute(refinedConfidenceDevice,
+ m_pImpl->m_fusedDisparityDevice,
+ stream);
+ }
+ }
+#ifdef NVBENCH_ENABLE
+ }
+#endif
+
+ // Running the post-processing
+ if(runPostProcessing)
+ {
+ m_pImpl->m_postprocess->execute(disparityConfidence,
+ m_pImpl->m_disparityConfidenceDevice,
+ stream);
+ }
+}
+
+void Bi3D::execute(detail::DisparityConfidence & disparityConfidence,
+ const detail::InputImage & leftImage,
+ const detail::InputImage & rightImage,
+ const detail::DisparityLevels & disparityLevels,
+ cudaStream_t stream)
+{
+ // Running the preprocessing
+ m_pImpl->m_preprocess->execute(m_pImpl->m_preprocessedLeftImageDevice,
+ m_pImpl->m_preprocessedRightImageDevice,
+ leftImage,
+ rightImage,
+ stream);
+
+ // Running processing
+ this->execute(disparityConfidence,
+ m_pImpl->m_preprocessedLeftImageDevice,
+ m_pImpl->m_preprocessedRightImageDevice,
+ disparityLevels, stream);
+}
+
+void Bi3D::execute(detail::QuantizedDisparity & quantizedDisparity,
+ const detail::InputImage & leftImage,
+ const detail::InputImage & rightImage,
+ const detail::DisparityLevels & disparityLevels,
+ cudaStream_t stream)
+{
+#ifdef NVBENCH_ENABLE
+ const std::string testName = "Bi3DU8_batch" +
+ std::to_string(1) + "_" +
+ std::to_string(leftImage.getWidth()) + "x" +
+ std::to_string(leftImage.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ // Ensuring the buffers are appropreately allocated
+ m_pImpl->resizeBuffers(leftImage.getWidth(), leftImage.getHeight());
+
+ // Calling the floating point version of this method
+ this->execute(m_pImpl->m_disparityConfidenceExchangeDevice,
+ leftImage, rightImage, disparityLevels,
+ stream);
+
+ // Converting the confidence to U8
+ detail::ConvertBitDepth(m_pImpl->m_quantizedDisparityDevice,
+ m_pImpl->m_disparityConfidenceExchangeDevice,
+ 255.0, stream);
+
+ // Copying the results to output
+ detail::QuantizedDisparity partial{quantizedDisparity.getWidth(),
+ quantizedDisparity.getHeight(),
+ quantizedDisparity.getChannelCount(),
+ m_pImpl->m_quantizedDisparityDevice.getData(),
+ m_pImpl->m_quantizedDisparityDevice.isCPU()};
+ Copy(quantizedDisparity, partial, stream);
+}
+
+}} // namespace cvcore::bi3d
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPostProcessor.cpp b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPostProcessor.cpp
new file mode 100644
index 0000000..2ece996
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPostProcessor.cpp
@@ -0,0 +1,160 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include
+
+#include "Bi3D_detail.h"
+
+#include
+
+#ifdef NVBENCH_ENABLE
+#include
+#include
+#endif
+
+#include
+
+namespace cvcore { namespace bi3d {
+
+struct Bi3DPostProcessor::Bi3DPostProcessorImpl
+{
+ mutable detail::DisparityConfidence m_disparityConfidenceDevice;
+ mutable detail::DisparityConfidence m_disparityConfidenceThresholdDevice;
+ mutable detail::DisparityConfidence m_disparityConfidenceResizeDevice;
+
+ ModelInputParams m_modelParams;
+ Bi3D::Bi3DParams m_params;
+
+ Bi3DPostProcessorImpl(const ModelInputParams & modelInputParams,
+ const Bi3D::Bi3DParams & bi3dParams,
+ cudaStream_t stream)
+ : m_modelParams{modelInputParams}, m_params{bi3dParams}
+ {
+ m_disparityConfidenceDevice = {modelInputParams.inputLayerWidth,
+ modelInputParams.inputLayerHeight,
+ bi3dParams.maxDisparityLevels,
+ false};
+
+ m_disparityConfidenceThresholdDevice = {modelInputParams.inputLayerWidth,
+ modelInputParams.inputLayerHeight,
+ bi3dParams.maxDisparityLevels,
+ false};
+ }
+
+ void resizeBuffers(std::size_t width, std::size_t height)
+ {
+ if(m_disparityConfidenceResizeDevice.getDimCount() > 0 &&
+ m_disparityConfidenceResizeDevice.getWidth() == width &&
+ m_disparityConfidenceResizeDevice.getHeight() == height)
+ {
+ return;
+ }
+
+ m_disparityConfidenceResizeDevice = {width, height,
+ m_disparityConfidenceDevice.getChannelCount(),
+ false};
+ }
+};
+
+// =============================================================================
+// Bi3D Frontend
+// =============================================================================
+
+Bi3DPostProcessor::Bi3DPostProcessor(const ModelInputParams & modelInputParams,
+ const Bi3D::Bi3DParams & bi3dParams,
+ cudaStream_t stream)
+ : m_pImpl{new Bi3DPostProcessorImpl(modelInputParams, bi3dParams, stream)} {}
+
+Bi3DPostProcessor::~Bi3DPostProcessor() {}
+
+void Bi3DPostProcessor::execute(detail::DisparityConfidence & disparityConfidence,
+ detail::DisparityConfidence & rawDisparityConfidence,
+ cudaStream_t stream)
+{
+#ifdef NVBENCH_ENABLE
+ const std::string testName = "Bi3DPostProcessor_batch" +
+ std::to_string(m_pImpl->m_modelParams.maxBatchSize) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ // Ensuring the buffers are appropreately allocated
+ m_pImpl->resizeBuffers(disparityConfidence.getWidth(), disparityConfidence.getHeight());
+
+#ifdef NVBENCH_ENABLE
+ {
+ const std::string testName = "Bi3DPostProcessorTransformBlock_batch" +
+ std::to_string(m_pImpl->m_modelParams.maxBatchSize) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+ if(m_pImpl->m_params.sigmoidPostProcessing == ProcessingControl::ENABLE)
+ {
+ detail::Sigmoid(m_pImpl->m_disparityConfidenceDevice,
+ rawDisparityConfidence, stream);
+
+ if(m_pImpl->m_params.thresholdPostProcessing == ProcessingControl::ENABLE)
+ {
+ detail::Threshold(m_pImpl->m_disparityConfidenceThresholdDevice,
+ m_pImpl->m_disparityConfidenceDevice,
+ m_pImpl->m_params.thresholdValueLow,
+ m_pImpl->m_params.thresholdValueHigh,
+ m_pImpl->m_params.threshold, stream);
+
+ detail::Resize(m_pImpl->m_disparityConfidenceResizeDevice,
+ m_pImpl->m_disparityConfidenceThresholdDevice,
+ tensor_ops::INTERP_LINEAR, stream);
+ }
+ else
+ {
+ detail::Resize(m_pImpl->m_disparityConfidenceResizeDevice,
+ m_pImpl->m_disparityConfidenceDevice,
+ tensor_ops::INTERP_LINEAR, stream);
+ }
+ }
+ else
+ {
+ if(m_pImpl->m_params.thresholdPostProcessing == ProcessingControl::ENABLE)
+ {
+ detail::Threshold(m_pImpl->m_disparityConfidenceThresholdDevice,
+ rawDisparityConfidence,
+ m_pImpl->m_params.thresholdValueLow,
+ m_pImpl->m_params.thresholdValueHigh,
+ m_pImpl->m_params.threshold, stream);
+
+ detail::Resize(m_pImpl->m_disparityConfidenceResizeDevice,
+ m_pImpl->m_disparityConfidenceThresholdDevice,
+ tensor_ops::INTERP_LINEAR, stream);
+ }
+ else
+ {
+ detail::Resize(m_pImpl->m_disparityConfidenceResizeDevice,
+ rawDisparityConfidence,
+ tensor_ops::INTERP_LINEAR, stream);
+ }
+ }
+#ifdef NVBENCH_ENABLE
+ }
+#endif
+
+ detail::DisparityConfidence partial{disparityConfidence.getWidth(),
+ disparityConfidence.getHeight(),
+ disparityConfidence.getChannelCount(),
+ m_pImpl->m_disparityConfidenceResizeDevice.getData(),
+ m_pImpl->m_disparityConfidenceResizeDevice.isCPU()};
+ Copy(disparityConfidence, partial, stream);
+}
+
+}} // namespace cvcore::bi3d
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPreProcessor.cpp b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPreProcessor.cpp
new file mode 100644
index 0000000..796c709
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3DPreProcessor.cpp
@@ -0,0 +1,157 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include
+
+#include "Bi3D_detail.h"
+
+#include
+
+#ifdef NVBENCH_ENABLE
+#include
+#include
+#endif
+
+#include
+
+namespace cvcore { namespace bi3d {
+
+struct Bi3DPreProcessor::Bi3DPreProcessorImpl
+{
+ mutable detail::InputImage m_leftImageDevice;
+ mutable detail::InputImage m_rightImageDevice;
+ mutable detail::PreprocessedImage m_preLeftImageDevice;
+ mutable detail::PreprocessedImage m_preRightImageDevice;
+ mutable detail::InputImage m_leftImageResizeDevice;
+ mutable detail::InputImage m_rightImageResizeDevice;
+
+ // Operation(s)
+ detail::NormalizeFunctor m_normalizer;
+
+ // Needed parameters for pre-processing
+ ImagePreProcessingParams m_preProcessorParams;
+ ModelInputParams m_modelParams;
+
+ Bi3DPreProcessorImpl(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ cudaStream_t stream)
+ : m_preProcessorParams{preProcessorParams},
+ m_modelParams{modelInputParams},
+ m_normalizer{modelInputParams.inputLayerWidth, modelInputParams.inputLayerHeight}
+ {
+ // Configuring the top-level model input(s)
+ m_leftImageResizeDevice = {modelInputParams.inputLayerWidth,
+ modelInputParams.inputLayerHeight,
+ false};
+ m_rightImageResizeDevice = {modelInputParams.inputLayerWidth,
+ modelInputParams.inputLayerHeight,
+ m_leftImageResizeDevice.isCPU()};
+ }
+
+ void resizeBuffers(std::size_t width, std::size_t height)
+ {
+ if(m_leftImageDevice.getDimCount() > 0 &&
+ m_leftImageDevice.getWidth() == width &&
+ m_leftImageDevice.getHeight() == height)
+ {
+ return;
+ }
+
+ m_leftImageDevice = {width, height, false};
+ m_rightImageDevice = {width, height, false};
+ m_preLeftImageDevice = {width, height, false};
+ m_preRightImageDevice = {width, height, false};
+ }
+};
+
+// =============================================================================
+// Bi3D Frontend
+// =============================================================================
+
+Bi3DPreProcessor::Bi3DPreProcessor(const ImagePreProcessingParams & preProcessorParams,
+ const ModelInputParams & modelInputParams,
+ cudaStream_t stream)
+ : m_pImpl{new Bi3DPreProcessorImpl(preProcessorParams, modelInputParams, stream)} {}
+
+Bi3DPreProcessor::~Bi3DPreProcessor() {}
+
+void Bi3DPreProcessor::execute(detail::PreprocessedImage & preprocessedLeftImage,
+ detail::PreprocessedImage & preprocessedRightImage,
+ const detail::InputImage & leftImage,
+ const detail::InputImage & rightImage,
+ cudaStream_t stream)
+{
+#ifdef NVBENCH_ENABLE
+ const std::string testName = "Bi3DPreProcessor_batch" +
+ std::to_string(m_pImpl->m_modelParams.maxBatchSize) + "_" +
+ std::to_string(leftImage.getWidth()) + "x" +
+ std::to_string(leftImage.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ // Ensuring the buffers are appropreately allocated
+ m_pImpl->resizeBuffers(leftImage.getWidth(), leftImage.getHeight());
+
+ // Ensuring data is on the GPU
+ Copy(m_pImpl->m_leftImageDevice, leftImage, stream);
+ Copy(m_pImpl->m_rightImageDevice, rightImage, stream);
+
+ // Resizing the data to model input size
+ tensor_ops::Resize(m_pImpl->m_leftImageResizeDevice, m_pImpl->m_leftImageDevice,
+ false, tensor_ops::INTERP_LINEAR, stream);
+ tensor_ops::Resize(m_pImpl->m_rightImageResizeDevice, m_pImpl->m_rightImageDevice,
+ false, tensor_ops::INTERP_LINEAR, stream);
+
+ // Normalize (data whiten) the images
+ m_pImpl->m_normalizer(preprocessedLeftImage, m_pImpl->m_leftImageResizeDevice,
+ m_pImpl->m_preProcessorParams.pixelMean,
+ m_pImpl->m_preProcessorParams.stdDev,
+ stream);
+ m_pImpl->m_normalizer(preprocessedRightImage, m_pImpl->m_rightImageResizeDevice,
+ m_pImpl->m_preProcessorParams.pixelMean,
+ m_pImpl->m_preProcessorParams.stdDev,
+ stream);
+}
+
+void Bi3DPreProcessor::execute(detail::PreprocessedImage & preprocessedLeftImage,
+ detail::PreprocessedImage & preprocessedRightImage,
+ const detail::PreprocessedImage & leftImage,
+ const detail::PreprocessedImage & rightImage,
+ cudaStream_t stream)
+{
+#ifdef NVBENCH_ENABLE
+ const std::string testName = "Bi3DPreProcessor_batch" +
+ std::to_string(m_pImpl->m_modelParams.maxBatchSize) + "_" +
+ std::to_string(leftImage.getWidth()) + "x" +
+ std::to_string(leftImage.getHeight()) + "_GPU";
+ nv::bench::Timer timerFunc = nv::bench::GPU(testName.c_str(), nv::bench::Flag::DEFAULT, stream);
+#endif
+
+ // Ensuring the buffers are appropreately allocated
+ m_pImpl->resizeBuffers(leftImage.getWidth(), leftImage.getHeight());
+
+ Copy(m_pImpl->m_preLeftImageDevice, leftImage, stream);
+ Copy(m_pImpl->m_preRightImageDevice, rightImage, stream);
+
+ // Resizing the data to model input size
+ detail::Resize(preprocessedLeftImage, m_pImpl->m_preLeftImageDevice,
+ tensor_ops::INTERP_LINEAR, stream);
+ detail::Resize(preprocessedLeftImage, m_pImpl->m_preRightImageDevice,
+ tensor_ops::INTERP_LINEAR, stream);
+}
+
+}} // namespace cvcore::bi3d
\ No newline at end of file
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.cpp b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.cpp
new file mode 100644
index 0000000..602c50e
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.cpp
@@ -0,0 +1,196 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include "Bi3D_detail.h"
+
+#include
+#include
+
+#include
+#include
+#include
+
+namespace cvcore { namespace bi3d { namespace detail {
+
+void _pad(Tensor & dst, const Tensor & src,
+ int topBorderHeight, int leftBorderWidth, cudaStream_t stream)
+{
+ // Using NPP function: ``nppiCopyConstBorder_32f_C1R_Ctx''
+ // Spec ==> NppStatus nppiCopyConstBorder_32f_C1R_Ctx(const Npp32f * pSrc,
+ // int nSrcStep,
+ // NppiSize oSrcSizeROI,
+ // Npp32f * pDst,
+ // int nDstStep,
+ // NppiSize oDstSizeROI,
+ // int nTopBorderHeight,
+ // int nLeftBorderWidth,
+ // Npp32f nValue,
+ // NppStreamContext nppStreamCtx)
+ //
+ // Parameters
+ // pSrc Source-Image Pointer.
+ // nSrcStep Source-Image Stride in bytes.
+ // oSrcSizeROI Size (width, height) of the source region in pixels.
+ // pDst Destination-Image Pointer.
+ // nDstStep Destination-Image Stride in bytes.
+ // oDstSizeROI Size (width, height) of the destination region, i.e. the region that gets
+ // filled with data from the source image (inner part) and constant border
+ // color (outer part).
+ // nTopBorderHeight Height (in pixels) of the top border. The number of pixel rows at the top
+ // of the destination ROI that will be filled with the constant border
+ // color. nBottomBorderHeight = oDstSizeROI.height - nTopBorderHeight -
+ // oSrcSizeROI.height.
+ // nLeftBorderWidth Width (in pixels) of the left border. The width of the border at the
+ // right side of the destination ROI is implicitly defined by the size of
+ // the source ROI: nRightBorderWidth = oDstSizeROI.width - nLeftBorderWidth
+ // - oSrcSizeROI.width.
+ // nValue The pixel value to be set for border pixels for single channel functions.
+ // nppStreamCtx NPP Application Managed Stream Context.
+ nppiCopyConstBorder_32f_C1R_Ctx(
+ static_cast(src.getData()),
+ src.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(src.getWidth()), static_cast(src.getHeight())},
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ topBorderHeight, leftBorderWidth, 0.0, tensor_ops::GetNppStreamContext(stream));
+}
+
+void _threshold(Tensor & dst, const Tensor & src,
+ float valueLow, float valueHigh, float thresholdValue,
+ cudaStream_t stream)
+{
+ // Using NPP function: ``nppiThreshold_LTValGTVal_32f_C1R_Ctx''
+ // Spec ==> NppStatus nppiThreshold_LTValGTVal_32f_C1R_Ctx(const Npp32f * pSrc,
+ // int nSrcStep,
+ // Npp32f * pDst,
+ // int nDstStep,
+ // NppiSize oSizeROI,
+ // Npp32f nThresholdLT,
+ // Npp32f nValueLT,
+ // Npp32f nThresholdGT,
+ // Npp32f nValueGT,
+ // NppStreamContext nppStreamCtx)
+ //
+ // Parameters
+ // pSrc Source-Image Pointer.
+ // nSrcStep Source-Image Stride in bytes.
+ // pDst Destination-Image Pointer.
+ // nDstStep Destination-Image Stride in bytes.
+ // oSizeROI Size (width, height) of the destination region, i.e. the region that gets
+ // filled with data from the source image
+ // nThresholdLT The thresholdLT value.
+ // nValueLT The thresholdLT replacement value.
+ // nThresholdGT The thresholdGT value.
+ // nValueGT The thresholdGT replacement value.
+ // nppStreamCtx NPP Application Managed Stream Context.
+ nppiThreshold_LTValGTVal_32f_C1R_Ctx(
+ static_cast(src.getData()),
+ src.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ thresholdValue * (1.0 + std::numeric_limits::epsilon()), valueLow,
+ thresholdValue, valueHigh,
+ tensor_ops::GetNppStreamContext(stream));
+}
+
+void _clear(Tensor & dst, cudaStream_t stream)
+{
+ // Using NPP function: ``nppiSet_32f_C1R_Ctx''
+ // Spec ==> NppStatus nppiSet_32f_C1R_Ctx(const Npp32f nValue
+ // Npp32f * pDst,
+ // int nDstStep,
+ // NppiSize oSizeROI,
+ // NppStreamContext nppStreamCtx)
+ //
+ // Parameters
+ // nValue The pixel value to be set.
+ // pDst Destination-Image Pointer.
+ // nDstStep Destination-Image Stride in bytes.
+ // oSizeROI Size (width, height) of the destination region, i.e. the region that gets
+ // filled with nValue.
+ // nppStreamCtx NPP Application Managed Stream Context.
+ nppiSet_32f_C1R_Ctx(
+ 0.0,
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ tensor_ops::GetNppStreamContext(stream));
+}
+
+void _sigmoid(Tensor & dst, Tensor & src,
+ cudaStream_t stream)
+{
+ auto context = tensor_ops::GetNppStreamContext(stream);
+
+ // This is a bit of a complex series of operations, here's an exact model
+ //
+ // Explicit:
+ // DST = exp(-1 * ln(1 + exp(-1 * SRC)))
+ //
+ // Properties:
+ // 1) exp(ln(x)) = x
+ // 2) ln(x^y) = y * ln(x)
+ // 3) x^(-1) = 1 / x
+ //
+ // Expected:
+ // DST = 1 / (1 + exp(-1 * SRC))
+ nppiMulC_32f_C1R_Ctx(
+ static_cast(src.getData()),
+ src.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ -1.0,
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+ nppiExp_32f_C1IR_Ctx(
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+ nppiAddC_32f_C1IR_Ctx(
+ 1.0,
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+ nppiLn_32f_C1IR_Ctx(
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+ nppiMulC_32f_C1IR_Ctx(
+ -1.0,
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+ nppiExp_32f_C1IR_Ctx(
+ static_cast(dst.getData()),
+ dst.getStride(TensorDimension::HEIGHT) * sizeof(float),
+ {static_cast(dst.getWidth()), static_cast(dst.getHeight())},
+ context);
+}
+
+void _sigmoid(Tensor & dst, Tensor & src)
+{
+ std::transform(src.getData(), src.getData() + src.getDataSize() / sizeof(float),
+ dst.getData(), [](float value) -> float {return 1.0 / (1.0 + std::exp(-1.0 * value));});
+}
+
+}}} // namespace cvcore::bi3d::detail
diff --git a/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.h b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.h
new file mode 100644
index 0000000..df612c3
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/3dv/src/Bi3D_detail.h
@@ -0,0 +1,340 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef CVCORE_BI3D_DETAIL_H_
+#define CVCORE_BI3D_DETAIL_H_
+
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+namespace cvcore { namespace bi3d { namespace detail {
+
+using DisparityLevels = Array;
+using InputImage = Tensor;
+using PreprocessedImage = traits::to_planar_t>;
+using BatchPreprocessedImage = traits::add_batch_t;
+using FeatureResponse = Tensor;
+using BatchFeatureResponse = traits::add_batch_t;
+using ConfidenceMap = Tensor;
+using GuidedConfidence = traits::to_cx_t;
+using RefinedConfidence = Tensor;
+using DisparityConfidence = traits::to_cx_t;
+using QuantizedDisparity = traits::to_u8_t;
+
+using NormalizeFunctor = tensor_ops::ImageToNormalizedPlanarTensorOperator;
+
+void _pad(Tensor & dst, const Tensor & src,
+ int topBorderHeight, int leftBorderWidth, cudaStream_t stream);
+
+template
+void Pad(Tensor & dst, Tensor & src,
+ const Array & topBorderHeights, const Array & leftBorderWidths,
+ cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _pad(_dst, _src, topBorderHeights[c], leftBorderWidths[c], stream);
+ }
+}
+
+template
+void Pad(Tensor & dst, Tensor & src,
+ const Array & topBorderHeights, int leftBorderWidth, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _pad(_dst, _src, topBorderHeights[c], leftBorderWidth, stream);
+ }
+}
+
+template
+void Pad(Tensor & dst, Tensor & src,
+ int topBorderHeight, const Array & leftBorderWidths, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _pad(_dst, _src, topBorderHeight, leftBorderWidths[c], stream);
+ }
+}
+
+template
+void Pad(Tensor & dst, Tensor & src,
+ int topBorderHeight, int leftBorderWidth, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _pad(_dst, _src, topBorderHeight, leftBorderWidth, stream);
+ }
+}
+
+template
+void Pad(Tensor & dst, Tensor & src,
+ int topBorderHeight, int leftBorderWidth, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t n = 0; n < dst.getDepth(); ++n)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(), dst.getChannelCount(),
+ dst.getData() + n*dst.getStride(TensorDimension::DEPTH),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(), src.getChannelCount(),
+ src.getData() + n*src.getStride(TensorDimension::DEPTH),
+ src.isCPU()};
+
+ Pad(_dst, _src, topBorderHeight, leftBorderWidth, stream);
+ }
+}
+
+void _threshold(Tensor & dst, const Tensor & src,
+ float valueLow, float valueHigh, float thresholdValue,
+ cudaStream_t stream);
+
+template
+void Threshold(Tensor & dst, Tensor & src,
+ float valueLow, float valueHigh, float thresholdValue,
+ cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ TensorType _dst{dst.getWidth(), dst.getHeight() * dst.getChannelCount(),
+ dst.getData(), dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight() * src.getChannelCount(),
+ src.getData(), src.isCPU()};
+
+ _threshold(_dst, _src, valueLow, valueHigh, thresholdValue, stream);
+}
+
+template
+void Threshold(Tensor & dst, Tensor & src,
+ float valueLow, float valueHigh, float thresholdValue,
+ cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getChannelCount() * dst.getDepth(),
+ dst.getData(), dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getChannelCount() * src.getDepth(),
+ src.getData(), src.isCPU()};
+
+ Threshold(_dst, _src, valueLow, valueHigh, thresholdValue, stream);
+}
+
+template
+void CropAndResize(Tensor & dst, Tensor & src,
+ const BBox & dstROI, const BBox & srcROI,
+ tensor_ops::InterpolationType type, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ tensor_ops::CropAndResize(_dst, _src, dstROI, srcROI, type, stream);
+ }
+}
+
+template
+void CropAndResize(Tensor & dst, Tensor & src,
+ const BBox & dstROI, const BBox & srcROI,
+ tensor_ops::InterpolationType type, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t n = 0; n < dst.getDepth(); ++n)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(), dst.getChannelCount(),
+ dst.getData() + n*dst.getStride(TensorDimension::DEPTH),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(), src.getChannelCount(),
+ src.getData() + n*src.getStride(TensorDimension::DEPTH),
+ src.isCPU()};
+
+ CropAndResize(_dst, _src, dstROI, srcROI, type, stream);
+ }
+}
+
+template
+void Resize(Tensor & dst, Tensor & src,
+ tensor_ops::InterpolationType type, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ tensor_ops::Resize(_dst, _src, false, type, stream);
+ }
+}
+
+template
+void Resize(Tensor & dst, Tensor & src,
+ tensor_ops::InterpolationType type, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t n = 0; n < dst.getDepth(); ++n)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(), dst.getChannelCount(),
+ dst.getData() + n*dst.getStride(TensorDimension::DEPTH),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(), src.getChannelCount(),
+ src.getData() + n*src.getStride(TensorDimension::DEPTH),
+ src.isCPU()};
+
+ Resize(_dst, _src, type, stream);
+ }
+}
+
+void _clear(Tensor & dst, cudaStream_t stream);
+
+template
+void Clear(Tensor & dst, cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+
+ _clear(_dst, stream);
+ }
+}
+
+template
+void ConvertBitDepth(Tensor & dst, Tensor & src,
+ float scale, cudaStream_t stream)
+{
+ using TensorSrcType = Tensor;
+ using TensorDstType = traits::to_u8_t;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorDstType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorSrcType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ tensor_ops::ConvertBitDepth(_dst, _src, scale, stream);
+ }
+}
+
+void _sigmoid(Tensor & dst, Tensor & src,
+ cudaStream_t stream);
+
+void _sigmoid(Tensor & dst, Tensor & src);
+
+template
+void Sigmoid(Tensor & dst, Tensor & src,
+ cudaStream_t stream)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _sigmoid(_dst, _src, stream);
+ }
+}
+
+template
+void Sigmoid(Tensor & dst, Tensor & src)
+{
+ using TensorType = Tensor;
+
+ for(std::size_t c = 0; c < dst.getChannelCount(); ++c)
+ {
+ TensorType _dst{dst.getWidth(), dst.getHeight(),
+ dst.getData() + c*dst.getStride(TensorDimension::CHANNEL),
+ dst.isCPU()};
+ TensorType _src{src.getWidth(), src.getHeight(),
+ src.getData() + c*src.getStride(TensorDimension::CHANNEL),
+ src.isCPU()};
+
+ _sigmoid(_dst, _src);
+ }
+}
+
+}}} // namespace cvcore::bi3d::detail
+
+#endif // CVCORE_BI3D_DETAIL_H_
diff --git a/isaac_ros_bi3d/gxf/bi3d/CMakeLists.txt b/isaac_ros_bi3d/gxf/bi3d/CMakeLists.txt
new file mode 100644
index 0000000..52c607a
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/CMakeLists.txt
@@ -0,0 +1,135 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+#
+# SPDX-License-Identifier: Apache-2.0
+
+project(gxf_cvcore_bi3d LANGUAGES C CXX CUDA)
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-fPIC -w)
+endif()
+
+# Dependencies
+find_package(CUDAToolkit)
+include(YamlCpp)
+find_package(GXF ${ISAAC_ROS_GXF_VERSION} MODULE REQUIRED
+ COMPONENTS
+ core
+ cuda
+ multimedia
+ serialization
+ std
+)
+find_package(TENSORRT)
+
+# Create extension
+add_library(gxf_cvcore_bi3d SHARED
+ extensions/bi3d/Bi3D.cpp
+ extensions/bi3d/Bi3D.hpp
+ extensions/bi3d/Bi3DRegistry.cpp
+
+ extensions/tensor_ops/ImageAdapter.cpp
+ extensions/tensor_ops/ImageAdapter.hpp
+ extensions/tensor_ops/ImageUtils.cpp
+ extensions/tensor_ops/ImageUtils.hpp
+
+ extensions/tensor_ops/detail/ImageAdapterTensorImpl.cpp
+ extensions/tensor_ops/detail/ImageAdapterTensorImpl.hpp
+ extensions/tensor_ops/detail/ImageAdapterVideoBufferImpl.cpp
+ extensions/tensor_ops/detail/ImageAdapterVideoBufferImpl.hpp
+)
+
+set(CMAKE_INCLUDE_CURRENT_DIR TRUE)
+target_include_directories(gxf_cvcore_bi3d PRIVATE
+ ${CMAKE_CURRENT_SOURCE_DIR}/cvcore/include
+ ${CMAKE_CURRENT_SOURCE_DIR}/3dv/include)
+
+
+add_library(cvcore_bi3d STATIC
+ # Tensorops
+ cvcore/src/tensor_ops/ArithmeticOperations.cpp
+ cvcore/src/tensor_ops/BBoxUtils.cpp
+ cvcore/src/tensor_ops/ColorConversions.cpp
+ cvcore/src/tensor_ops/DBScan.cpp
+ cvcore/src/tensor_ops/Errors.cpp
+ cvcore/src/tensor_ops/Filters.cpp
+ cvcore/src/tensor_ops/Filters.h
+ cvcore/src/tensor_ops/FusedOperations.cpp
+ cvcore/src/tensor_ops/GeometryTransforms.cpp
+ cvcore/src/tensor_ops/IImageWarp.cpp
+ cvcore/src/tensor_ops/NppUtils.cpp
+ cvcore/src/tensor_ops/NppUtils.h
+ cvcore/src/tensor_ops/OneEuroFilter.cpp
+ cvcore/src/tensor_ops/TensorOperators.cpp
+
+ # Core
+ cvcore/src/core/cvcore/Array.cpp
+ cvcore/src/core/cvcore/Dummy.cu
+ cvcore/src/core/cvcore/MathTypes.cpp
+ cvcore/src/core/cvcore/Tensor.cpp
+ cvcore/src/core/utility/CVError.cpp
+ cvcore/src/core/utility/Instrumentation.cpp
+ cvcore/src/core/utility/Memory.cpp
+ cvcore/src/core/utility/ProfileUtils.cpp
+
+ # Inferencer (Bi3d only)
+ cvcore/src/inferencer/tensorrt/TensorRTInferencer.cpp
+ cvcore/src/inferencer/Inferencer.cpp
+ cvcore/src/inferencer/Errors.cpp
+ cvcore/src/inferencer/tensorrt/TensorRTUtils.h
+ cvcore/src/inferencer/tensorrt/TensorRTUtils.cpp
+ cvcore/src/inferencer/tensorrt/TensorRTInferencer.h
+
+ # TRTBackend
+ cvcore/src/trtbackend/TRTBackend.cpp
+)
+
+target_include_directories(cvcore_bi3d PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/cvcore/include)
+target_compile_options(cvcore_bi3d PUBLIC -fPIC)
+target_link_libraries(cvcore_bi3d PUBLIC
+ CUDA::cudart
+ CUDA::nppc
+ CUDA::nppial
+ CUDA::nppicc
+ CUDA::nppidei
+ CUDA::nppif
+ CUDA::nppig
+ CUDA::nppisu
+ CUDA::nppitc
+ TENSORRT::nvinfer
+)
+
+add_library(bi3d_3dv STATIC
+ 3dv/src/Bi3D_detail.cpp
+ 3dv/src/Bi3D_detail.h
+ 3dv/src/Bi3D.cpp
+ 3dv/src/Bi3DPostProcessor.cpp
+ 3dv/src/Bi3DPreProcessor.cpp
+)
+target_include_directories(bi3d_3dv PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/3dv/include)
+target_compile_options(bi3d_3dv PUBLIC -fPIC)
+target_link_libraries(bi3d_3dv PUBLIC
+ cvcore_bi3d
+)
+target_link_libraries(gxf_cvcore_bi3d
+ PUBLIC
+ GXF::cuda
+ GXF::multimedia
+ GXF::std
+ yaml-cpp
+ PRIVATE
+ cvcore_bi3d
+ bi3d_3dv
+)
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/CMakeLists.txt b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/CMakeLists.txt
new file mode 100644
index 0000000..e165480
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/CMakeLists.txt
@@ -0,0 +1,51 @@
+# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+# Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+#
+# SPDX-License-Identifier: Apache-2.0
+
+cmake_minimum_required(VERSION 3.23.2)
+project(gxf_bi3d_postprocessor LANGUAGES C CXX)
+
+# Create extension
+add_library(gxf_bi3d_postprocessor SHARED
+ bi3d_postprocessor_extension.cpp
+ bi3d_postprocess/bi3d_message_splitter.cpp
+ bi3d_postprocess/bi3d_message_splitter.hpp
+ bi3d_postprocessor_utils.hpp
+ bi3d_postprocess/bi3d_postprocessor.cpp
+ bi3d_postprocess/bi3d_postprocessor.cu.cpp
+ bi3d_postprocess/bi3d_postprocessor.cu.hpp
+ bi3d_postprocess/bi3d_postprocessor.hpp
+)
+
+# Mark as CUDA files with non-standard extensions
+set_source_files_properties(
+ bi3d_postprocess/bi3d_postprocessor.cu.cpp
+ bi3d_postprocess/bi3d_postprocessor.cu.hpp
+ PROPERTIES
+ LANGUAGE CUDA
+)
+
+find_package(CUDAToolkit REQUIRED)
+
+set(CMAKE_INCLUDE_CURRENT_DIR TRUE)
+
+target_link_libraries(gxf_bi3d_postprocessor
+ PUBLIC
+ GXF::cuda
+ GXF::multimedia
+ GXF::std
+ yaml-cpp
+)
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.cpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.cpp
new file mode 100644
index 0000000..00ad8f7
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.cpp
@@ -0,0 +1,67 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include "gxf/std/parameter_parser_std.hpp"
+#include "gxf/std/timestamp.hpp"
+#include "gxf/multimedia/video.hpp"
+#include "bi3d_message_splitter.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+gxf_result_t Bi3DMessageSplitter::registerInterface(gxf::Registrar * registrar) noexcept
+{
+ gxf::Expected result;
+ result &= registrar->parameter(
+ receiver_, "receiver", "Receiver",
+ "Message from Bi3D post processor");
+ result &= registrar->parameter(
+ disparity_image_transmitter_, "disparity_image_transmitter", "Disparity image transmitter",
+ "The collapsed output of Bi3D");
+ result &= registrar->parameter(
+ disparity_values_transmitter_, "disparity_values_transmitter", "Disparity values transmitter",
+ "The disparity values used for Bi3D inference");
+ return gxf::ToResultCode(result);
+}
+
+gxf_result_t Bi3DMessageSplitter::tick() noexcept
+{
+ // Receive bi3d post processor output
+ auto bi3d_postprocessed_message = receiver_->receive();
+ if (!bi3d_postprocessed_message) {
+ GXF_LOG_ERROR("Failed to get message");
+ return gxf::ToResultCode(bi3d_postprocessed_message);
+ }
+
+ // Publish message
+ auto result = disparity_image_transmitter_->publish(bi3d_postprocessed_message.value());
+ if (!result) {
+ return gxf::ToResultCode(result);
+ }
+ result = disparity_values_transmitter_->publish(bi3d_postprocessed_message.value());
+ if (!result) {
+ return gxf::ToResultCode(result);
+ }
+
+ return GXF_SUCCESS;
+
+}
+
+} // namespace isaac_ros
+} // namespace nvidia
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.hpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.hpp
new file mode 100644
index 0000000..b642f30
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_message_splitter.hpp
@@ -0,0 +1,50 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_MESSAGE_SPLITTER_HPP_
+#define NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_MESSAGE_SPLITTER_HPP_
+
+#include "gxf/std/allocator.hpp"
+#include "gxf/std/codelet.hpp"
+#include "gxf/std/receiver.hpp"
+#include "gxf/std/transmitter.hpp"
+
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+// GXF codelet that takes the postprocessed output of Bi3D and splits it into disparity image and disparity values
+class Bi3DMessageSplitter : public gxf::Codelet
+{
+public:
+ gxf_result_t registerInterface(gxf::Registrar * registrar) noexcept override;
+ gxf_result_t start() noexcept override {return GXF_SUCCESS;}
+ gxf_result_t tick() noexcept override;
+ gxf_result_t stop() noexcept override {return GXF_SUCCESS;}
+
+private:
+ gxf::Parameter> receiver_;
+ gxf::Parameter> disparity_image_transmitter_;
+ gxf::Parameter> disparity_values_transmitter_;
+};
+
+} // namespace isaac_ros
+} // namespace nvidia
+
+#endif // NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_MESSAGE_SPLITTER_HPP_
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cpp
new file mode 100644
index 0000000..740eeba
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cpp
@@ -0,0 +1,178 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#include "gxf/std/parameter_parser_std.hpp"
+#include "gxf/std/timestamp.hpp"
+#include "bi3d_postprocessor.hpp"
+#include "bi3d_postprocessor_utils.hpp"
+#include "bi3d_postprocessor.cu.hpp"
+
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+gxf_result_t Bi3DPostprocessor::registerInterface(gxf::Registrar * registrar) noexcept
+{
+ gxf::Expected result;
+ result &= registrar->parameter(
+ bi3d_receiver_, "bi3d_receiver", "Bi3D input",
+ "Tensor from Bi3D");
+ result &= registrar->parameter(
+ output_transmitter_, "output_transmitter", "Output transmitter",
+ "The collapsed output of Bi3D");
+ result &= registrar->parameter(
+ pool_, "pool", "Pool",
+ "Allocator instance for output videobuffer");
+ result &= registrar->parameter(
+ disparity_values_, "disparity_values", "Disparity values",
+ "Fixed disparity values used for Bi3D inference",
+ gxf::Registrar::NoDefaultParameter(), GXF_PARAMETER_FLAGS_OPTIONAL);
+ result &= registrar->parameter(
+ disparity_tensor_name_, "disparity_tensor_name", "Disparity tensor name",
+ "Name of the disparity tensor from Bi3D");
+ result &= registrar->parameter(
+ disparity_values_tensor_name_, "disparity_values_tensor_name", "Disparity values tensor name",
+ "Name of the (dynamic) disparity values tensor from Bi3D",
+ gxf::Registrar::NoDefaultParameter(), GXF_PARAMETER_FLAGS_OPTIONAL);
+ return gxf::ToResultCode(result);
+}
+
+gxf_result_t Bi3DPostprocessor::start() noexcept
+{
+ auto fixed_disparity_values = disparity_values_.try_get();
+ auto disparity_values_name = disparity_values_tensor_name_.try_get();
+ if (fixed_disparity_values && disparity_values_name) {
+ GXF_LOG_WARNING(
+ "Both fixed disparity values and dynamic disparity values given. Fixed disparity values will be used.");
+ }
+ return GXF_SUCCESS;
+}
+
+gxf_result_t Bi3DPostprocessor::tick() noexcept
+{
+ // Receive bi3d output
+ auto bi3d_message = bi3d_receiver_->receive();
+ if (!bi3d_message) {
+ GXF_LOG_ERROR("Failed to get message");
+ return gxf::ToResultCode(bi3d_message);
+ }
+
+ // Create output message
+ auto out_message = gxf::Entity::New(context());
+ if (!out_message) {
+ GXF_LOG_ERROR("Failed to allocate message");
+ return gxf::ToResultCode(out_message);
+ }
+
+ // Get Bi3D disparity tensor
+ auto bi3d_disparity_tensor = bi3d_message->get(disparity_tensor_name_.get().c_str());
+ if (!bi3d_disparity_tensor) {
+ GXF_LOG_ERROR("Failed to get disparity image tensor");
+ return gxf::ToResultCode(bi3d_disparity_tensor);
+ }
+ if (!bi3d_disparity_tensor.value()->data()) {
+ GXF_LOG_ERROR("Failed to get pointer to bi3d disparity data");
+ return gxf::ToResultCode(bi3d_disparity_tensor.value()->data());
+ }
+ const float * bi3d_disparity_data_ptr = bi3d_disparity_tensor.value()->data().value();
+
+
+ // Get disparity values used for Bi3D inference
+ int disparity_count;
+ const int * disparity_values_data;
+
+ auto fixed_disparity_values = disparity_values_.try_get();
+ if (fixed_disparity_values) {
+ disparity_count = fixed_disparity_values.value().size();
+ disparity_values_data = fixed_disparity_values.value().data();
+ } else {
+ auto disparity_values_name = disparity_values_tensor_name_.try_get();
+ if (!disparity_values_name) {
+ GXF_LOG_ERROR("Neither dynamic nor fixed disparity values specified");
+ return GXF_FAILURE;
+ }
+ auto bi3d_disparity_value_tensor = bi3d_message->get(
+ disparity_values_name.value().c_str());
+ if (!bi3d_disparity_value_tensor) {
+ GXF_LOG_ERROR("Failed to get disparity values tensor");
+ return gxf::ToResultCode(bi3d_disparity_value_tensor);
+ }
+ disparity_count = bi3d_disparity_value_tensor.value()->element_count();
+ disparity_values_data = bi3d_disparity_value_tensor.value()->data().value();
+
+ // Add dynamic disparity value tensor to output message
+ auto forwarded_disp_values = out_message.value().add(
+ bi3d_disparity_value_tensor->name());
+ *forwarded_disp_values.value() = std::move(*bi3d_disparity_value_tensor.value());
+ }
+
+ // Get dimensions of tensor
+ gxf::Shape dims = bi3d_disparity_tensor.value()->shape();
+ const int image_height = dims.dimension(1);
+ const int image_width = dims.dimension(2);
+ const int image_size = dims.dimension(1) * dims.dimension(2);
+
+ // Create video buffer
+ auto out_video_buffer = out_message.value().add();
+ if (!out_video_buffer) {
+ GXF_LOG_ERROR("Failed to allocate output video buffer");
+ return gxf::ToResultCode(out_video_buffer);
+ }
+
+ // Allocate video buffer on device (unpadded gray32)
+ auto maybe_allocation = AllocateVideoBuffer(
+ out_video_buffer.value(), image_width, image_height, gxf::MemoryStorageType::kDevice,
+ pool_.get());
+ if (!maybe_allocation) {
+ GXF_LOG_ERROR("Failed to allocate output video buffer's memory.");
+ return gxf::ToResultCode(maybe_allocation);
+ }
+
+ cudaMemset(
+ out_video_buffer.value()->pointer(), 0,
+ image_size * bi3d_disparity_tensor.value()->bytes_per_element());
+
+ for (int i = 0; i < disparity_count; i++) {
+ cuda_postprocess(
+ bi3d_disparity_data_ptr + (i * image_size),
+ (float *)out_video_buffer.value()->pointer(), disparity_values_data[i], image_height,
+ image_width);
+ }
+
+ // Add timestamp
+ std::string timestamp_name{"timestamp"};
+ auto maybe_bi3d_timestamp = bi3d_message->get();
+ if (!maybe_bi3d_timestamp) {
+ GXF_LOG_ERROR("Failed to get a timestamp from Bi3D output");
+ }
+ auto out_timestamp = out_message.value().add(timestamp_name.c_str());
+ if (!out_timestamp) {return GXF_FAILURE;}
+ *out_timestamp.value() = *maybe_bi3d_timestamp.value();
+
+ // Publish message
+ auto result = output_transmitter_->publish(out_message.value());
+ if (!result) {
+ return gxf::ToResultCode(result);
+ }
+
+ return GXF_SUCCESS;
+}
+
+} // namespace isaac_ros
+} // namespace nvidia
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.cpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.cpp
new file mode 100644
index 0000000..931525b
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.cpp
@@ -0,0 +1,54 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+#include "bi3d_postprocessor.cu.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+__global__ void postprocessing_kernel(
+ const float * input, float * output, int disparity,
+ int imageHeight, int imageWidth)
+{
+ const uint32_t x = blockIdx.x * blockDim.x + threadIdx.x;
+ const uint32_t y = blockIdx.y * blockDim.y + threadIdx.y;
+ const uint32_t index = y * imageWidth + x;
+ if (x < imageWidth && y < imageHeight) {
+ if (input[index] == 1.0) {
+ output[index] = input[index] * disparity;
+ }
+ }
+}
+
+uint16_t ceil_div(uint16_t numerator, uint16_t denominator)
+{
+ uint32_t accumulator = numerator + denominator - 1;
+ return accumulator / denominator;
+}
+
+void cuda_postprocess(
+ const float * input, float * output, int disparity, int imageHeight,
+ int imageWidth)
+{
+ dim3 block(16, 16);
+ dim3 grid(ceil_div(imageWidth, 16), ceil_div(imageHeight, 16), 1);
+ postprocessing_kernel << < grid, block >> > (input, output, disparity, imageHeight, imageWidth);
+}
+
+} // namespace isaac_ros
+} // namespace nvidia
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.hpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.hpp
new file mode 100644
index 0000000..6c7de9c
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.cu.hpp
@@ -0,0 +1,38 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+#ifndef NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_CU_HPP_
+#define NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_CU_HPP_
+
+#include
+#include
+
+#include "cuda.h"
+#include "cuda_runtime.h"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+void cuda_postprocess(
+ const float * input, float * output, int disparity, int imageHeight,
+ int imageWidth);
+
+} // namespace isaac_ros
+} // namespace nvidia
+
+#endif // NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_CU_HPP_
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.hpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.hpp
new file mode 100644
index 0000000..6fb5e28
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocess/bi3d_postprocessor.hpp
@@ -0,0 +1,55 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_HPP_
+#define NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_HPP_
+
+#include
+
+#include "gxf/std/allocator.hpp"
+#include "gxf/std/codelet.hpp"
+#include "gxf/std/receiver.hpp"
+#include "gxf/std/transmitter.hpp"
+
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+// GXF codelet that takes Bi3D output tensor list and collapses it into single segmentation image
+class Bi3DPostprocessor : public gxf::Codelet
+{
+public:
+ gxf_result_t registerInterface(gxf::Registrar * registrar) noexcept override;
+ gxf_result_t start() noexcept override;
+ gxf_result_t tick() noexcept override;
+ gxf_result_t stop() noexcept override {return GXF_SUCCESS;}
+
+private:
+ gxf::Parameter> bi3d_receiver_;
+ gxf::Parameter> output_transmitter_;
+ gxf::Parameter> pool_;
+ gxf::Parameter> disparity_values_;
+ gxf::Parameter disparity_tensor_name_;
+ gxf::Parameter disparity_values_tensor_name_;
+};
+
+} // namespace isaac_ros
+} // namespace nvidia
+
+#endif // NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_HPP_
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_extension.cpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_extension.cpp
new file mode 100644
index 0000000..ebe5ee6
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_extension.cpp
@@ -0,0 +1,45 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+#include
+
+#include "gxf/core/gxf.h"
+#include "gxf/std/extension_factory_helper.hpp"
+#include "bi3d_postprocess/bi3d_postprocessor.hpp"
+#include "bi3d_postprocess/bi3d_message_splitter.hpp"
+
+extern "C" {
+
+GXF_EXT_FACTORY_BEGIN()
+
+GXF_EXT_FACTORY_SET_INFO(
+ 0xb764a9fce34d11ec, 0x8fea0242ac120002, "Bi3DPostprocessorExtension",
+ "Bi3D Post Processing GXF extension",
+ "NVIDIA", "1.0.0", "LICENSE");
+
+GXF_EXT_FACTORY_ADD(
+ 0xa8a24ecde2544d6a, 0x9a4b81cdb71085d6,
+ nvidia::isaac_ros::Bi3DPostprocessor, nvidia::gxf::Codelet,
+ "Collapses Bi3D output tensorlist to single segmentation image");
+
+GXF_EXT_FACTORY_ADD(
+ 0xa8a24ecde2564d6a, 0x9a4b89cdb71085d6,
+ nvidia::isaac_ros::Bi3DMessageSplitter, nvidia::gxf::Codelet,
+ "Splits Bi3D postprocessor output into disparity image and disparity values");
+
+GXF_EXT_FACTORY_END()
+
+} // extern "C"
diff --git a/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_utils.hpp b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_utils.hpp
new file mode 100644
index 0000000..d6d64c5
--- /dev/null
+++ b/isaac_ros_bi3d/gxf/bi3d/bi3d_postprocessor/bi3d_postprocessor_utils.hpp
@@ -0,0 +1,87 @@
+// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
+// Copyright (c) 2022-2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+//
+// SPDX-License-Identifier: Apache-2.0
+#ifndef NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_UTILS_HPP_
+#define NVIDIA_ISAAC_ROS_EXTENSIONS_BI3D_POSTPROCESSOR_UTILS_HPP_
+
+#include
+
+#include "gxf/multimedia/video.hpp"
+#include "gxf/std/allocator.hpp"
+
+namespace nvidia
+{
+namespace isaac_ros
+{
+
+template
+inline constexpr uint8_t GetChannelSize();
+
+template<>
+inline constexpr uint8_t GetChannelSize()
+{
+ return 1;
+}
+
+template<>
+inline constexpr uint8_t GetChannelSize()
+{
+ return 4;
+}
+
+template
+inline const char * GetColorName();
+
+template<>
+inline const char * GetColorName()
+{
+ return "gray";
+}
+
+template<>
+inline const char * GetColorName()
+{
+ return "gray";
+}
+
+template