Skip to content

Latest commit

 

History

History
65 lines (51 loc) · 14.2 KB

topics-and-services.md

File metadata and controls

65 lines (51 loc) · 14.2 KB

ROS Topics and Services

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

Note: The examples in the Isaac Sim and realsense human reconstruction tutorials launch the nvblox_human_node, while the standard Isaac Sim and realsense tutorials launch the nvblox_node. The nvblox_human_node inherits from the nvblox_node and extends its capabilities.

ROS Topics Subscribed

ROS Topic Interface Description
pointcloud sensor_msgs/PointCloud2 Input 3D LIDAR pointcloud. Make sure to set the lidar_height, lidar_width, and lidar_vertical_fov_rad 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/camera_info sensor_msgs/CameraInfo Required topic along with the depth image. Contains intrinsic calibration parameters of the depth 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).
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 nvblox human examples 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.
~/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.
~/occupancy sensor_msgs/PointCloud2 A pointcloud of the occupancy map (only voxels with occupation probability > 0.5). Set occupancy_publication_rate_hz to control its publication rate.
~/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.
~/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.
~/mesh_marker visualization_msgs/Marker A visualization topic showing the mesh using a marker message.

Additionally published topics by the nvblox_human_node:

ROS Topic Interface Description
~/human_pointcloud sensor_msgs/PointCloud2 Pointcloud visualizing the back-projected pixels of the latest human masked depth frame (without temporal fusion).
~/human_voxels visualization_msgs/Marker The pointcloud published at ~/human_pointcloud mapped to the corresponding voxels.
~/human_occupancy sensor_msgs/PointCloud2 A pointcloud of the human occupancy map (only voxels with occupation probability > 0.5).
~/human_esdf_pointcloud sensor_msgs/PointCloud2 A pointcloud of the human 2D ESDF (Euclidean Signed Distance Field), with intensity as the metric distance to the nearest human. Set human_esdf_update_rate_hz to control its update rate.
~/combined_esdf_pointcloud sensor_msgs/PointCloud2 A pointcloud of the combined static and human 2D ESDF (minimal distance of both), with intensity as the metric distance to the nearest obstacle or human. Set human_esdf_update_rate_hz to control its update rate.
~/human_map_slice nvblox_msgs/DistanceMapSlice A 2D slice of the human ESDF, to be consumed by nvblox_nav2 package for interfacing with Nav2. Set human_esdf_update_rate_hz to control its update rate.
~/combined_map_slice nvblox_msgs/DistanceMapSlice A 2D slice of the combined static and human ESDF (minimal distance of both), to be consumed by nvblox_nav2 package for interfacing with Nav2. Set human_esdf_update_rate_hz to control its update rate.
~/depth_frame_overlay sensor_msgs/Image Debug image showing the mask overlaid on the depth image.
~/color_frame_overlay sensor_msgs/Image Debug image showing the 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'}"