isaac_ros_bi3d
Source code on GitHub.
Quickstart
Set up your development environment by following the instructions here.
Clone
isaac_ros_common
and this repository under${ISAAC_ROS_WS}/src
.cd ${ISAAC_ROS_WS}/src
git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git
git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_depth_segmentation.git
Pull down a rosbag of sample data:
cd ${ISAAC_ROS_WS}/src/isaac_ros_depth_segmentation && git lfs pull -X "" -I "resources/rosbags/bi3dnode_rosbag"
Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && ./scripts/run_dev.sh
Install this package’s dependencies.
sudo apt-get install -y ros-humble-isaac-ros-bi3d
Download model files for Bi3D (refer to the Model Preparation section for more information):
mkdir -p /tmp/models/bi3d && cd /tmp/models/bi3d && wget 'https://api.ngc.nvidia.com/v2/models/nvidia/isaac/bi3d_proximity_segmentation/versions/2.0.0/files/featnet.onnx' && wget 'https://api.ngc.nvidia.com/v2/models/nvidia/isaac/bi3d_proximity_segmentation/versions/2.0.0/files/segnet.onnx'
Convert the
.onnx
model files to TensorRT engine plan files (refer to the Model Preparation section for more information):If using Jetson (Generate engine plans with DLA support enabled):
/usr/src/tensorrt/bin/trtexec --saveEngine=/tmp/models/bi3d/bi3dnet_featnet.plan \ --onnx=/tmp/models/bi3d/featnet.onnx \ --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 --allowGPUFallback
If using x86_64:
/usr/src/tensorrt/bin/trtexec --saveEngine=/tmp/models/bi3d/bi3dnet_featnet.plan \ --onnx=/tmp/models/bi3d/featnet.onnx --int8 && /usr/src/tensorrt/bin/trtexec --saveEngine=/tmp/models/bi3d/bi3dnet_segnet.plan \ --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.
Run the launch file to spin up a demo of this package:
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 \ image_height:=360 \ image_width:=640
Open a second terminal inside the Docker container:
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Play the rosbag file to simulate image streams from the cameras:
ros2 bag play --loop src/isaac_ros_depth_segmentation/resources/rosbags/bi3dnode_rosbag
Open two new terminals inside the Docker container for visualization:
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Visualize the output.
Start disparity visualizer:
ros2 run isaac_ros_bi3d isaac_ros_bi3d_visualizer.py --max_disparity_value 30
Start image visualizer:
ros2 run image_view image_view --ros-args -r image:=rgb_left
Try More Examples
To continue your exploration, check out the following suggested examples:
Model Preparation
Download Pre-trained Models (.onnx
) from NGC
The following steps show how to download pre-trained Bi3D DNN inference models.
The following model files must be downloaded to perform Bi3D inference. From File Browser on the Bi3D page, select the following
.onnx
model files in the FILE list and copy thewget
command by clicking … in the ACTIONS column:featnet.onnx
segnet.onnx
Run each of the copied commands in a terminal to download the ONNX model file, as shown in the example below:
wget 'https://api.ngc.nvidia.com/v2/models/nvidia/isaac/bi3d_proximity_segmentation/versions/2.0.0/files/featnet.onnx' && wget 'https://api.ngc.nvidia.com/v2/models/nvidia/isaac/bi3d_proximity_segmentation/versions/2.0.0/files/segnet.onnx'
Bi3D Featnet is a network that extracts features from stereo images.
Bi3D Segnet is an encoder-decoder segmentation network that generates a binary segmentation confidence map.
Convert the Pre-trained Models (.onnx
) to TensorRT Engine Plans
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.
Generating Engine Plans for Jetson
/usr/src/tensorrt/bin/trtexec --onnx=<PATH_TO_ONNX_MODEL_FILE> --saveEngine=<PATH_TO_WHERE_TO_SAVE_ENGINE_PLAN> --useDLACore=<SET_CORE_TO_ENABLE_DLA> --int8 --allowGPUFallback
Generating Engine Plans for x86_64
/usr/src/tensorrt/bin/trtexec --onnx=<PATH_TO_ONNX_MODEL_FILE> --saveEngine=<PATH_TO_WHERE_TO_SAVE_ENGINE_PLAN> --int8
Troubleshooting
Isaac ROS Troubleshooting
For solutions to problems with Isaac ROS, please check here.
Deep Learning Troubleshooting
For solutions to problems with using DNN models, please check here.
API
Usage
ros2 launch isaac_ros_bi3d isaac_ros_bi3d.launch.py featnet_engine_file_path:=<PATH_TO_FEATNET_ENGINE> \
segnet_engine_file_path:=<PATH_TO_SEGNET_ENGINE \
max_disparity_values:=<MAX_NUMBER_OF_DISPARITY_VALUES_USED> \
image_height:=<INPUT_IMAGE_HEIGHT> \
image_width:=<INPUT_IMAGE_WIDTH>
Interpreting the Output
The isaas_ros_bi3d
package outputs a disparity image given a list of
disparity values (planes). Each pixel of the output image that is not
freespace is set to the value of the closest disparity plane (largest
disparity value) that the pixel is deemed to be in front of. Each pixel
that is predicted to be freespace is set to 0 (the furthest
disparity/smallest disparity value). Freespace is defined as the region
from the bottom of the image, up to the first pixel above which is not
the ground plane. To find the boundary between freespace and
not-freespace, one may start from the bottom of the image and, per
column, find the first pixel that is not the ground plane. In the below
example, the freespace of the image is shown in black:
The prediction of freespace eliminates the need for ground plane removal
in the output image as a post-processing step, which is often applied to
other stereo disparity functions. The output of isaas_ros_bi3d
can
be used to check if any pixels within the image breach a given proximity
field by checking the values of all pixels. If a pixel value (disparity
value) is larger than the disparity plane defining the proximity field,
then it has breached that field. If a pixel does not breach any of the
provided disparity planes, it is assigned a value of 0.
ROS Parameters
ROS Parameter |
Type |
Default |
Description |
---|---|---|---|
|
|
|
The height of the input image |
|
|
|
The width of the input image |
|
|
|
The path to the Bi3D Featnet engine plan |
|
|
|
The path to the Bi3D Segnet engine plan |
|
|
|
The maximum number of disparity values used for Bi3D inference. Isaac ROS Depth Segmentation supports up to a theoretical maximum of 64 disparity values during inference. However, the maximum length of disparities that a user may run in practice is dependent on the user’s hardware and availability of memory. |
|
|
|
The specific threshold disparity values used for Bi3D inference. The number of disparity values must not exceed the value set in the |
ROS Topics Subscribed
ROS Topic |
Interface |
Description |
---|---|---|
|
|
|
|
|
|
|
Focal length populated in the Bi3D output disparity is extracted from this topic. |
|
|
Baseline populated in the Bi3D output disparity is extracted from this topic. |
Note
The images on input topics (left_image_bi3d
and right_image_bi3d
) should be a color image in rgb8
format.
ROS Topics Published
ROS Topic |
Interface |
Description |
---|---|---|
|
The depth 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 does not breach any disparity plane or if it is freespace. |