Nvblox is a package for building a 3D reconstruction of the environment around your robot from sensor observations in real-time. The reconstruction is intended to be used by path planners to generate collision-free paths. Under the hood, nvblox uses NVIDIA CUDA to accelerate this task to allow operation at real-time rates. This repository contains ROS2 integration for the nvblox core library.
Given a stream of depth images and the corresponding pose of the depth sensor, Isaac ROS Nvblox produces both a 2D distance map slice, representing the distance from each point to the nearest reconstructed object, and also a 3D mesh for visualization in RVIZ. An optional RGB stream can also be used to color the reconstruction for visualization.
Read more about Nvblox's technical details here.
The figure below shows a simple system utilizing nvblox for path planning.
- Isaac ROS Nvblox (Preview)
Update 2022-10-19: Updated OSS licensing
This package is designed and tested to be compatible with ROS2 Humble running on Jetson 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.
Platform | Hardware | Software | Notes |
---|---|---|---|
Jetson | Jetson Orin Jetson Xavier |
JetPack 5.0.2 | For best performance, ensure that power settings are configured appropriately. |
x86_64 | NVIDIA GPU | Ubuntu 20.04+ CUDA 11.6.1+ |
To simplify development, we strongly recommend leveraging the Isaac ROS Dev Docker images by following these steps. This will streamline your development environment setup with the correct versions of dependencies on both Jetson and x86_64 platforms.
Note: All Isaac ROS Quickstarts, tutorials, and examples have been designed with the Isaac ROS Docker images as a prerequisite.
-
Set up your development environment by following the instructions here.
-
Clone this repository and its dependencies under
~/workspaces/isaac_ros-dev/src
.cd ~/workspaces/isaac_ros-dev/src
git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common
git clone -b ros2-beta https://github.com/IntelRealSense/realsense-ros
git clone --recurse-submodules https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_nvblox && \ cd isaac_ros_nvblox && git lfs pull
-
Configure the container created by
isaac_ros_common/scripts/run_dev.sh
to includelibrealsense
. Create the.isaac_ros_common-config
file in theisaac_ros_common/scripts
directory:cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common/scripts && \ touch .isaac_ros_common-config && \ echo CONFIG_IMAGE_KEY=humble.nav2.realsense > .isaac_ros_common-config
-
Pull down a ROS Bag of sample data:
cd ~/workspaces/isaac_ros-dev/src/isaac_ros_nvblox && \ git lfs pull -X "" -I "nvblox_ros/test/test_cases/rosbags/nvblox_pol"
-
Launch the Docker container using the
run_dev.sh
script:cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \ ./scripts/run_dev.sh
-
Inside the container, install package-specific dependencies via
rosdep
:cd /workspaces/isaac_ros-dev/ && \ rosdep install -i -r --from-paths src --rosdistro humble -y --skip-keys "libopencv-dev libopencv-contrib-dev libopencv-imgproc-dev python-opencv python3-opencv nvblox"
-
Build and source the workspace:
cd /workspaces/isaac_ros-dev && \ colcon build --symlink-install && \ source install/setup.bash
-
(Optional) Run tests to verify complete and correct installation:
colcon test --executor sequential
-
In a current terminal inside the Docker container, run the launch file for Nvblox with
nav2
:source /workspaces/isaac_ros-dev/install/setup.bash && \ ros2 launch nvblox_nav2 carter_sim.launch.py
-
Open a second terminal inside the docker container:
cd ~/workspaces/isaac_ros-dev/src/isaac_ros_common && \ ./scripts/run_dev.sh
-
In the second terminal, play the ROS Bag:
ros2 bag play src/isaac_ros_nvblox/nvblox_ros/test/test_cases/rosbags/nvblox_pol
You should see the robot reconstructing a mesh, with a costmap overlaid on top.
To continue your exploration, check out the following suggested examples:
To customize your development environment, reference this guide.
ros2 launch nvblox_nav2 carter_sim.launch.py
ROS Parameter | Type | Default | Description |
---|---|---|---|
voxel_size |
float |
0.05 |
Voxel size (in meters) to use for the map. |
esdf |
bool |
true |
Whether to compute the ESDF (map of distances to the nearest obstacle). |
esdf_2d |
bool |
true |
Whether to compute the ESDF in 2D (true) or 3D (false). |
distance_slice |
bool |
true |
Whether to output a distance slice of the ESDF to be used for path planning. |
mesh |
bool |
true |
Whether to output a mesh for visualization in rviz, to be used with nvblox_rviz_plugin . |
global_frame |
string |
map |
The name of the TF frame to be used as the global frame. |
slice_height |
float |
1.0 |
The output slice height for the distance slice and ESDF pointcloud. Does not need to be within min and max height below. In units of meters. |
min_height |
float |
0.0 |
The minimum height, in meters, to consider obstacles part of the 2D ESDF slice. |
max_height |
float |
1.0 |
The maximum height, in meters, to consider obstacles part of the 2D ESDF slice. |
max_tsdf_update_hz |
float |
10.0 |
The maximum rate (in Hz) at which to integrate depth images into the TSDF. A value of 0.0 means there is no cap. |
max_color_update_hz |
float |
5.0 |
The maximum rate (in Hz) at which to integrate color images into the color layer. A value of 0.0 means there is no cap. |
max_mesh_update_hz |
float |
5.0 |
The maximum rate (in Hz) at which to update and color the mesh. A value of 0.0 means there is no cap. |
max_esdf_update_hz |
float |
2.0 |
The maximum rate (in Hz) at which to update the ESDF and output the distance slice. A value of 0.0 means there is no cap. |
tsdf_integrator_max_integration_distance_m |
float |
10.0 |
The maximum distance, in meters, to integrate the TSDF up to. |
tsdf_integrator_truncation_distance_vox |
float |
4.0 |
The truncation distance, in units of voxels, for the TSDF. |
tsdf_integrator_max_weight |
float |
100.0 |
Maximum weight for the TSDF. Setting this number higher will lead to higher-quality reconstructions but worse performance in dynamic scenes. |
mesh_integrator_min_weight |
float |
1e-4 |
Minimum weight of the TSDF to consider for inclusion in the mesh. |
mesh_integrator_weld_vertices |
bool |
false |
Whether to weld identical vertices together in the mesh. Currently reduces the number of vertices by a factor of 5x, but is quite slow so we do not recommend you use this setting. |
color_integrator_max_integration_distance_m |
float |
10.0 |
Maximum distance, in meters, to integrate the color up to. |
esdf_integrator_min_weight |
float |
1e-4 |
Minimum weight of the TSDF to consider for inclusion in the ESDF. |
esdf_integrator_min_site_distance_vox |
float |
1.0 |
Minimum distance to consider a voxel within a surface for the ESDF calculation. |
esdf_integrator_max_distance_m |
float |
10.0 |
Maximum distance to compute the ESDF up to, in meters. |
ROS Topic | Interface | Description |
---|---|---|
depth/image |
sensor_msgs/Image | The input depth image to be integrated. Must be paired with a camera_info message below. Supports both floating-point (depth in meters) and uint16 (depth in millimeters, OpenNI format). |
depth/camera_info |
sensor_msgs/CameraInfo | Required topic along with the depth image; contains intrinsic calibration parameters of the depth camera. |
color/image |
sensor_msgs/Image | Optional input color image to be integrated. Must be paired with a camera_info message below. Only used to color the mesh. |
color/camera_info |
sensor_msgs/CameraInfo | Optional topic along with the color image above, contains intrinsics of the color camera. |
ROS Topic | Interface | Description |
---|---|---|
mesh |
nvblox_msgs/Mesh | A visualization topic showing the mesh produced from the TSDF in a form that can be seen in RViz using nvblox_rviz_plugin . Set max_mesh_update_hz to control its update rate. |
pointcloud |
sensor_msgs/PointCloud2 | A pointcloud of the 2D ESDF (Euclidean Signed Distance Field), with intensity as the metric distance to the nearest obstacle. Set max_esdf_update_hz to control its update rate. |
map_slice |
nvblox_msgs/DistanceMapSlice | A 2D slice of the ESDF, to be consumed by nvblox_nav2 package for interfacing with Nav2. Set max_esdf_update_hz to control its update rate. |
ROS Service | Interface | Description |
---|---|---|
save_ply |
std_srvs/Empty | This service has an empty request and response. Calling this service will write a mesh to disk at the path specified by the output_dir parameter. |
For solutions to problems with Isaac ROS, please check here.
Please follow the workaround here.
Date | Changes |
---|---|
2022-10-19 | Updated OSS licensing |
2022-08-31 | Update to be compatible with JetPack 5.0.2. Serialization of nvblox maps to file. Support for 3D LIDAR input and performace improvements. |
2022-06-30 | Support for ROS2 Humble and miscellaneous bug fixes. |
2022-03-21 | Initial version. |