Attention

As of June 30, 2025, the Isaac ROS Buildfarm for Isaac ROS 2.1 on Ubuntu 20.04 Focal is no longer supported.

Due to an isolated infrastructure event, all ROS 2 Humble Debian packages that were previously built for Ubuntu 20.04 are no longer available in the Isaac Apt Repository. All artifacts for Isaac ROS 3.0 and later are built and maintained with a more robust pipeline.

Users are encouraged to migrate to the latest version of Isaac ROS. The source code for Isaac ROS 2.1 continues to be available on the release-2.1 branches of the Isaac ROS GitHub repositories.

The original documentation for Isaac ROS 2.1 is preserved below.

ROS Topics and Services

Find all topics and services of the nvblox_node and the nvblox_human_node below.

Note

The human reconstruction tutorials (Isaac Sim / realsense) launch the nvblox_human_node, while the static reconstruction tutorials (Isaac Sim / realsense) as well as the dynamic reconstruction tutorials (Isaac Sim / realsense) launch the nvblox_node. The nvblox_human_node inherits from the nvblox_node and is adding additional topic subscriptions for the mask image containing the human semantic segmentation.

ROS Topics Subscribed

ROS Topic

Interface

Description

pointcloud

sensor_msgs/PointCloud2

Input 3D LIDAR pointcloud. Make sure to set the lidar intrinsic parameters if using this input, as it uses those to convert the pointcloud into a depth image.

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.

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.

transform

geometry_message/TransformStamped

Odometry as stamped transform messages. Not required if use_tf_transforms is set to true.

pose

geometry_message/PoseStamped

Odometry as stamped pose messages. Not required if use_tf_transforms is set to true.

Additionally subscribed topics by the nvblox_human_node:

ROS Topic

Interface

Description

mask/image

sensor_msgs/Image

The mask image with the human segmentation (non-human pixels = 0 and human pixels = 1). In the Human Reconstruction with RealSense tutorial this is published by Isaac ROS Image Segmentation.

mask/camera_info

sensor_msgs/CameraInfo

Required topic along with the mask image. Contains intrinsic calibration parameters of the mask camera.

ROS Topics Published

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 mesh_update_rate_hz to control its update rate.

~/mesh_marker

visualization_msgs/Marker

A visualization topic showing the mesh using a marker message.

~/static_esdf_pointcloud

sensor_msgs/PointCloud2

A pointcloud of the static 2D ESDF (Euclidean Signed Distance Field), with intensity as the metric distance to the nearest obstacle. Set esdf_update_rate_hz to control its update rate.

~/static_map_slice

nvblox_msgs/DistanceMapSlice

A 2D slice of the static ESDF, to be consumed by nvblox_nav2 package for interfacing with Nav2. Set esdf_update_rate_hz to control its update rate.

~/static_occupancy

sensor_msgs/PointCloud2

A pointcloud of the static occupancy map (only voxels with occupation probability > 0.5). Set static_occupancy_publication_rate_hz to control its publication rate.

~/map_slice_bounds

visualization_msgs/Marker

A visualization topic showing the mesh slice bounds that can be set with the parameters esdf_2d_min_height and esdf_2d_min_height.

~/back_projected_depth

sensor_msgs/PointCloud2

A pointcloud of the back projected latest depth image in the global frame.

~/dynamic_occupancy

sensor_msgs/PointCloud2

A pointcloud of the human/dynamic occupancy map (only voxels with occupation probability > 0.5).

~/dynamic_esdf_pointcloud

sensor_msgs/PointCloud2

A pointcloud of the human/dynamic 2D ESDF (Euclidean Signed Distance Field), with intensity as the metric distance to the nearest human. Set esdf_update_rate_hz to control its update rate.

~/dynamic_map_slice

nvblox_msgs/DistanceMapSlice

A 2D slice of the human/dynamic ESDF, to be consumed by nvblox_nav2 package for interfacing with Nav2. Set esdf_update_rate_hz to control its update rate.

~/dynamic_points

sensor_msgs/PointCloud2

Pointcloud visualizing the back-projected pixels of the latest human/dynamic masked depth frame (without temporal fusion).

~/dynamic_depth_frame_overlay

sensor_msgs/Image

Debug image showing the dynamic/human mask overlaid on the depth image. Note: The overlay is showing the mask before postprocessing.

~/freespace

sensor_msgs/PointCloud2

Pointcloud visualizing all non high confidence freespace voxels inside a 5x5x1 m box around the depth camera.

~/combined_esdf_pointcloud

sensor_msgs/PointCloud2

A pointcloud of the combined static and human/dynamic 2D ESDF (minimal distance of both), with intensity as the metric distance to the nearest obstacle or human. Set esdf_update_rate_hz to control its update rate.

~/combined_map_slice

nvblox_msgs/DistanceMapSlice

A 2D slice of the combined static and human/dynamic ESDF (minimal distance of both), to be consumed by nvblox_nav2 package for interfacing with Nav2. Set esdf_update_rate_hz to control its update rate.

Additionally published topics by the nvblox_human_node:

ROS Topic

Interface

Description

~/human_voxels

visualization_msgs/Marker

The pointcloud published at ~/dynamic_points mapped to the corresponding voxels. Set human_debug_publish_rate_h to control its update rate.

~/dynamic_color_frame_overlay

sensor_msgs/Image

Debug image showing the human mask overlaid on the color image.

ROS Services Advertised

ROS Service

Interface

Description

~/save_ply

nvblox_msgs/FilePath

Will save the mesh as the PLY (standard polygon file format, which can be viewed with MeshLab or CloudCompare) at the specified location.

~/save_map

nvblox_msgs/FilePath

Will serialize the entire map, including TSDF, ESDF, etc., at the given location.

~/load_map

nvblox_msgs/FilePath

Will overwrite the current map in the node with a map loaded from the given path.

Example service calls from the command line:

ros2 service call /nvblox_node/save_ply nvblox_msgs/srv/FilePath "{file_path: '/home/USERNAME/super_cool_map.ply'}"
ros2 service call /nvblox_node/save_map nvblox_msgs/srv/FilePath "{file_path: '/home/USERNAME/super_cool_map.nvblx'}"
ros2 service call /nvblox_node/load_map nvblox_msgs/srv/FilePath "{file_path: '/home/USERNAME/super_cool_map.nvblx'}"