ROS Parameters

This page contains all parameters exposed to ROS 2. For the provided examples in the nvblox_example_bringup package, parameters are set using YAML configuration files under nvblox_examples/nvblox_examples_bringup/config.

The base parameters are set in nvblox_base.yaml and there exist multiple specialization files that overwrite parameters from the base file depending on the configuration of the launched example/mode.

File tree:

config
├── nvblox
    ├── nvblox_base.yaml
    └── specializations
        ├── nvblox_sim.yaml
        ├── nvblox_realsense.yaml
        ├── nvblox_multi_realsense.yaml
        ├── nvblox_segmentation.yaml
        ├── nvblox_detection.yaml
        └── nvblox_dynamics.yaml

Loaded specializations for each example/mode:

Parameter file

Example/mode

nvblox_sim.yaml

isaac_sim_example.launch.py

nvblox_realsense.yaml

realsense_example.launch.py

nvblox_multi_realsense.yaml

realsense_example.launch.py

nvblox_segmentation.yaml

mode:=people_segmentation

nvblox_detection.yaml

mode:=people_detection

nvblox_dynamics.yaml

mode:=dynamic

Renamed Isaac ROS Nvblox parameters

The following parameters have been removed or renamed since ISAAC 3.0. If you are re-using any customized parameter files from a previous release, make sure to update the parameters listed below.

Removed parameters

Removed Parameter

Note

enable_mesh_markers

Mesh markers not supported anymore.

layer_visualization_max_tsdf_distance_m

Value is now hard-coded.

human_debug_publish_rate_hz

Human debug output is published on receiving a depth frame now.

Renamed parameters

Old Parameter

New Parameter

maximum_sensor_message_queue_length

maximum_input_queue_length

<mapper_name>.mesh_bandwidth_limit_mbps

layer_streamer_bandwidth_limit_mbps

<mapper_name>.mesh_streamer_exclusion_height_m

<mapper_name>.layer_streamer_exclusion_height_m

<mapper_name>.mesh_streamer_exclusion_radius_m

<mapper_name>.layer_streamer_exclusion_radius_m

slice_visualization_attachment_frame_id

esdf_slice_bounds_visualization_attachment_frame_id

slice_visualization_side_length

esdf_slice_bounds_visualization_side_length

General Parameters

ROS Parameter

Type

Default

Description

after_shutdown_map_save_path

string

The path used to save the map after shutdown.

back_projection_subsampling

integer

1

Only back project and publish every n-th depth image.

clear_map_outside_radius_rate_hz

double

1.000

The desired rate for clearing the map from blocks far away from the robot.

connected_mask_component_size_threshold

integer

2000

Connected components smaller than this threshold will be removed from the mask image.

cuda_stream_type

integer

1

The CUDA stream type nvblox ROS node will create. Default option is a blocking asynchronous stream(1), we can also use CUDA default stream(0) or non blocking asynchronous stream(2) or per thread default stream(3)

decay_dynamic_occupancy_rate_hz

double

10.000

The desired rate for decaying the dynamic occupancy layer.

decay_tsdf_rate_hz

double

5.000

The desired rate for decaying the TSDF layer.

distance_map_unknown_value_optimistic

double

1000.000

The distance inside the distance map for unknown value.

distance_map_unknown_value_pessimistic

double

-1000.000

The distance inside the distance map for unknown value.

esdf_and_gradients_unobserved_value

double

-1000.000

This value will be used for for unobserved voxels in the dense output grid.

esdf_mode

string

2d

Whether to compute the ESDF in 2d or 3d.

esdf_slice_bounds_visualization_attachment_frame_id

string

base_link

Frame to which the ESDF slice bounds visualization is centered on the xy-plane.

esdf_slice_bounds_visualization_side_length

double

10.000

Side length of the ESDF slice bounds visualization plane.

global_frame

string

odom

The name of the TF frame in which the map is built. For the RealSense examples, this parameter is exposed as a launch argument.

input_qos

string

SYSTEM_DEFAULT

integrate_color_rate_hz

double

5.000

The desired integration frequency of color images.

integrate_depth_rate_hz

double

40.000

The desired integration frequency of depth images.

integrate_lidar_rate_hz

double

40.000

The desired integration frequency of lidar scans.

layer_streamer_bandwidth_limit_mbps

double

30.000

Bandwidth limit for streaming layer visualizations (over WiFi) in mega-bits per second.

layer_visualization_exclusion_height_m

double

2.000

Voxels with a z coordinate above this value are not visualized.

layer_visualization_exclusion_radius_m

double

5.000

Voxels further from the robot than this value are not visualized.

layer_visualization_min_tsdf_weight

double

0.100

TSDF voxels with a weight lower than this value are not visualized.

layer_visualization_undo_gamma_correction

boolean

False

Apply a undo-gamma operation on the RGB values of the visualized layer. Usable if the rendering pipeline includes gamma correction, which is the case when rendering mesh markers in Foxglove.

lidar_height

integer

16

Height of the LIDAR scan, in number of beams. Default works for the VLP16.

lidar_max_valid_range_m

double

50.000

The maximum valid range of the lidar.

lidar_min_valid_range_m

double

0.100

The minimum valid range of the lidar.

lidar_vertical_fov_rad

double

0.524

The vertical field of view of the LIDAR scan, in radians (assuming beams are centered around 0 elevation). Default is for the VLP16.

lidar_width

integer

1800

Width of the LIDAR scan, in number of beams. Default works for the VLP16.

map_clearing_frame_id

string

base_link

The name of the TF frame around which we clear the map.

map_clearing_radius_m

double

5.000

Radius around the map_clearing_frame_id outside which we clear the map. Note that values <= 0.0 indicate that no clearing is performed.

mapping_type

string

static_tsdf

Type of mapper to use. See docs for description

max_angle_above_zero_elevation_rad

double

0.262

The angle above zero elevation of the highest beam (specified as a positive number in radians). Default is for the Hesai PandarXT32.

max_back_projection_distance

double

5.000

The maximum depth in meters when visualizing the back-projected point cloud.

maximum_input_queue_length

integer

10

How many items to store in the input queues (depth, color, lidar, services) before deleting oldest items.

min_angle_below_zero_elevation_rad

double

0.349

The angle below zero elevation of the lowest beam (specified as a positive number in radians). Default is for the Hesai PandarXT32.

num_cameras

integer

1

Number of cameras supported (number of subscribers created)

output_pessimistic_distance_map

boolean

True

Whether or not to output the pessimistic distance map.

pose_frame

string

base_link

Only used if use_topic_transforms is set to true. Pose and transform messages will be interpreted as being in this pose frame, and the remaining transform to the sensor frame will be looked up on the TF tree.

print_delays_to_console

boolean

False

Whether to print delay stats to the console.

print_rates_to_console

boolean

False

Whether to print rate stats to the console.

print_statistics_on_console_period_ms

integer

10000

Specified how often to print timing and rate statistics to the terminal.

print_timings_to_console

boolean

False

Whether to print timing stats to the console.

publish_debug_vis_rate_hz

double

2.000

The desired rate for publishing debug visualization messages.

publish_esdf_distance_slice

boolean

True

Whether to output a distance slice of the ESDF to be used for path planning.

publish_layer_rate_hz

double

10.000

The desired rate for publishing layer visualization messages.

qos_overrides./parameter_events.publisher.depth

integer

1000

QoS policy {depth} for publisher {/parameter_events} Constraints: Read only: true

qos_overrides./parameter_events.publisher.durability

string

volatile

QoS policy {durability} for publisher {/parameter_events} Constraints: Read only: true

qos_overrides./parameter_events.publisher.history

string

keep_last

QoS policy {history} for publisher {/parameter_events} Constraints: Read only: true

qos_overrides./parameter_events.publisher.reliability

string

reliable

QoS policy {reliability} for publisher {/parameter_events} Constraints: Read only: true

remove_small_connected_components

boolean

True

If set to true, small connected components will be removed from the segmentation mask.

tick_period_ms

integer

10

Specifies How often the main tick function of the node is ticked.

update_esdf_rate_hz

double

5.000

The desired ESDF update frequency.

update_mesh_rate_hz

double

5.000

The desired mesh update frequency.

use_color

boolean

True

Whether to integrate color images to color the mesh.

use_depth

boolean

True

Whether to integrate depth images.

use_lidar

boolean

True

Whether to integrate LiDAR scans.

use_non_equal_vertical_fov_lidar_params

boolean

False

Whether to use non equal vertical FoV for the LiDAR (not centered around 0 elevation). Should be set to false for a VLP16 and to true for Hesai PandarXT32. The LiDAR model will use the lidar_vertical_fov_rad parameter if set to false and min_angle_below_zero_elevation_rad / max_angle_below_zero_elevation_rad if set to true.

use_segmentation

boolean

False

Whether to integrate segmentation masks.

use_sim_time

boolean

False

use_tf_transforms

boolean

True

use_topic_transforms

boolean

False

voxel_size

double

0.050

Voxel size (side of cube in meters) to use for the map.

workspace_height_bounds_visualization_attachment_frame_id

string

base_link

Frame to which the workspace height bounds visualization is centered on the xy-plane.

workspace_height_bounds_visualization_side_length

double

10.000

Side length of the workspace height bounds visualization plane.

Mapping Type Parameter

The nvblox node holds two individual mappers (contained in a multi-mapper object). Depth frames received by nvblox are passed to the multi-mapper and split into a static and dynamic part based on a mask image. While the static part is processed by the static_mapper, the dynamic part is handled by the dynamic_mapper.

Depending on the mapping_type parameter these mappers update different layers:

  • static_tsdf:
    • static_mapper: mapping static obstacles using a TSDF layer

    • dynamic_mapper: disabled

  • static_occupancy:
    • static_mapper: mapping static obstacles using an occupancy layer

    • dynamic_mapper: disabled

  • dynamic:
    • static_mapper: mapping static obstacles using a TSDF layer and updating a freespace layer (needed for dynamic mapping)

    • dynamic_mapper: mapping dynamic obstacles in an occupancy layer

  • human_with_static_tsdf:
    • static_mapper: mapping static obstacles using a TSDF layer

    • dynamic_mapper: mapping people in an occupancy layer

  • human_with_static_occupancy:
    • static_mapper: mapping static obstacles using an occupancy layer

    • dynamic_mapper: mapping people in an occupancy layer

The mapping_type must be specified as a string and defaults to static_tsdf.

Note

The mapping types [static_tsdf, static_occupancy, dynamic] are only valid when running the nvblox_node. In contrast, the mapping types [human_with_static_tsdf, human_with_static_occupancy] can only run with the nvblox_human_node. The nvblox_human_node is adding additional topic subscriptions for the mask image containing the people semantic segmentation.

Mapper Parameters

The static and dynamic mappers share the same parameter set. By specifying the parent parameter name <mapper_name>, the parameters can be set for the corresponding mapper (i.e. static_mapper or dynamic_mapper).

ROS Parameter

Type

Default

Description

<mapper_name>.check_neighborhood

boolean

True

Whether to check the occupancy of the neighboring voxels for the high confidence freespace update.

<mapper_name>.decay_integrator_deallocate_decayed_blocks

boolean

True

Whether or not to deallocate fully decayed blocks.

<mapper_name>.depth_preprocessing_num_dilations

integer

4

Number of times to run the invalid region dilation in the depth preprocessing pipeline (if do_depth_preprocessing is enabled).

<mapper_name>.do_depth_preprocessing

boolean

False

Whether or not to run the preprocessing pipeline on the input depth image. Currently, this preprocessing only consists of dilating invalid regions in the input depth image.

<mapper_name>.esdf_integrator_max_distance_m

double

2.000

Maximum distance to compute the ESDF up to, in meters.

<mapper_name>.esdf_integrator_max_site_distance_vox

double

1.000

Maximum distance to consider a voxel within a surface for the ESDF calculation.

<mapper_name>.esdf_integrator_min_weight

double

0.000

Minimum weight of the TSDF to consider for inclusion in the ESDF.

<mapper_name>.esdf_slice_height

double

1.000

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.

<mapper_name>.esdf_slice_max_height

double

1.000

The maximum height, in meters, to consider obstacles part of the 2D ESDF slice.

<mapper_name>.esdf_slice_min_height

double

0.000

The minimum height, in meters, to consider obstacles part of the 2D ESDF slice.

<mapper_name>.exclude_last_view_from_decay

boolean

False

Whether contributions from the last depth frame should be excluded when decaying

<mapper_name>.free_region_decay_probability

double

0.550

The decay probability that is applied to the free region on decay. Must be in [0.5, 1.0].

<mapper_name>.free_region_occupancy_probability

double

0.300

The inverse sensor model occupancy probability for voxels observed as free space.

<mapper_name>.layer_streamer_exclusion_height_m

double

-1.000

Blocks above this height will not be streamed.

<mapper_name>.layer_streamer_exclusion_radius_m

double

-1.000

Blocks outside this radius (centered on the robot) will not be streamed.

<mapper_name>.lidar_projective_integrator_max_integration_distance_m

double

10.000

The maximum distance, in meters, to integrate the depth values for LiDAR scans.

<mapper_name>.max_tsdf_distance_for_occupancy_m

double

0.150

TSDF distance below which we assume a voxel to be occupied (non freespace).

<mapper_name>.max_unobserved_to_keep_consecutive_occupancy_ms

integer

200

Maximum duration of no observed occupancy to keep consecutive occupancy alive.

<mapper_name>.mesh_integrator_min_weight

double

0.000

Minimum weight of the TSDF to consider for inclusion in the mesh.

<mapper_name>.mesh_integrator_weld_vertices

boolean

True

Whether to weld identical vertices together in the mesh.

<mapper_name>.min_consecutive_occupancy_duration_for_reset_ms

integer

2000

Minimum duration of consecutive occupancy to turn a high confidence free voxel back to occupied.

<mapper_name>.min_duration_since_occupied_for_freespace_ms

integer

1000

Minimum duration since last observed occupancy to consider voxel as free.

<mapper_name>.occupied_region_decay_probability

double

0.400

The decay probability that is applied to the occupied region on decay. Must be in [0.0, 0.5].

<mapper_name>.occupied_region_half_width_m

double

0.100

Half the width of the region which is considered as occupied.

<mapper_name>.occupied_region_occupancy_probability

double

0.700

The inverse sensor model occupancy probability for voxels observed as occupied.

<mapper_name>.projective_integrator_max_integration_distance_m

double

7.000

The maximum distance, in meters, to integrate the depth or color image values.

<mapper_name>.projective_integrator_max_weight

double

5.000

Maximum weight for the TSDF and color integrations. Setting this number higher will lead to higher-quality reconstructions but worse performance in dynamic scenes.

<mapper_name>.projective_tsdf_integrator_invalid_depth_decay_factor

double

0.800

Decay factor that is applied to the TSDF weigh to voxels projecting into pixels with invalid depth.

<mapper_name>.projective_integrator_truncation_distance_vox

double

4.000

The truncation distance, in units of voxels, for the TSDF or occupancy map.

<mapper_name>.projective_integrator_weighting_mode

string

kInverseSquareWeight

The weighting mode, applied to TSDF and color integrations. Options: [0:constant, 1:constant drop-off, 2:inverse square, 3:inverse square drop-off, 4:inverse square TSDF distance penalty]

<mapper_name>.raycast_subsampling_factor

integer

4

The rate at which we subsample pixels to raycast. Note that we always raycast the extremes of the frame, no matter the subsample rate.

<mapper_name>.tsdf_decay_factor

double

0.950

Decay factor that is applied to the TSDF weight when the TSDF decay is called.

<mapper_name>.tsdf_decayed_free_distance_vox

double

4.000

The distance in voxels that we give to fully decayed voxels (if requested).

<mapper_name>.tsdf_decayed_weight_threshold

double

0.001

The weight of a TSDF voxel below which we consider it fully decayed.

<mapper_name>.tsdf_set_free_distance_on_decayed

boolean

False

If true we set fully decayed voxels to the free distance.

<mapper_name>.unobserved_region_occupancy_probability

double

0.500

The inverse sensor model occupancy probability for unobserved voxels.

<mapper_name>.workspace_bounds_max_corner_x_m

double

0.000

The x-component of the maximal corner of the workspace bounds. Only used if workspace_bounds_type:=bounding_box.

<mapper_name>.workspace_bounds_max_corner_y_m

double

2.000

The y-component of the maximal corner of the workspace bounds. Only used if workspace_bounds_type:=bounding_box.

<mapper_name>.workspace_bounds_max_height_m

double

1.000

The maximal height of the workspace bounds.

<mapper_name>.workspace_bounds_min_corner_x_m

double

0.000

The x-component of the minimal corner of the workspace bounds. Only used if workspace_bounds_type:=bounding_box.

<mapper_name>.workspace_bounds_min_corner_y_m

double

2.000

The y-component of the minimal corner of the workspace bounds. Only used if workspace_bounds_type:=bounding_box.

<mapper_name>.workspace_bounds_min_height_m

double

0.000

The minimal height of the workspace bounds.

<mapper_name>.workspace_bounds_type

string

kUnbounded

The type of bounds we limit the workspace with (unbounded, height bounds or bounding box).

Note

Decay of the occupancy layer is needed to handle dynamic objects like people. Without the decay observed dynamic objects stay in the map even if not seen for a long time period. In that time the object might have moved and the map is therefore invalid. Using the decay we simulate the loss of knowledge about parts of the dynamic map currently not observed over time.