Issues with nvblox layer in nav2 costmap

Hello,

I am trying to run nav2 with nvblox. So my idea is to use 2D lidars for map and localization and use nvblox to detect low lying obstacles(or basically detect obstacles which 2D lidars cannot). I’m using nav2 with the ISAAC ROS MAP LOCALIZATION package to localize using 2D lidars. Everythings works but when I use nvblox on top of it, the obstacle detected by nvblox does not have inflation around it and because the robot crashes into the obstacle. It can detect the obstacle and plan a path to avoid it but since there is no inflation, the robot could not produce an optimum path.

I get this warning and apart from this, there is no error or warning displaying in nav2 or nvblox terminals:

[component_container_isolated-2] [WARN] [1727700807.002075203] [local_costmap.local_costmap]: [NvbloxCostmapLayer] Transformation from odom to map must be 2d, but it is 3d.

Please check the video( Dont mind the resoultion on isaac sim, I lowered it to consume less GPU usage)

These are my nav2 costmaps parameters:

local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      global_frame: odom
      robot_base_frame: base_link
      use_sim_time: True
      rolling_window: True
      width: 5
      height: 5
      resolution: 0.05
      footprint: "[ [0.14, 0.25], [0.14, -0.25], [-0.607, -0.25], [-0.607, 0.25] ]"
      plugins: ["inflation_layer", "nvblox_layer", "laser_scan"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 10.0
        inflation_radius: 0.8
      laser_scan:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      nvblox_layer:
        plugin: "nvblox::nav2::NvbloxCostmapLayer"
        enabled: True
        nav2_costmap_global_frame: odom 
        nvblox_map_slice_topic: "/nvblox_node/static_map_slice"
        convert_to_binary_costmap: True
      always_send_full_costmap: True
  local_costmap_client:
    ros__parameters:
      use_sim_time: True
  local_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: True

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map
      robot_base_frame: base_link
      use_sim_time: True
      rolling_window: True
      width: 200
      height: 200
      footprint: "[ [0.14, 0.25], [0.14, -0.25], [-0.607, -0.25], [-0.607, 0.25] ]"
      resolution: 0.05
      plugins: ["static_layer", "obstacle_layer", "inflation_layer", "nvblox_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 10.0
          raytrace_min_range: 0.0
          obstacle_max_range: 10.0
          obstacle_min_range: 0.0
      nvblox_layer:
        plugin: "nvblox::nav2::NvbloxCostmapLayer"
        enabled: True
        nav2_costmap_global_frame: map 
        nvblox_map_slice_topic: "/nvblox_node/static_map_slice"
        convert_to_binary_costmap: True
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 10.0
        inflation_radius: 0.8
      always_send_full_costmap: True
  global_costmap_client:
    ros__parameters:
      use_sim_time: True
  global_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: True

These are my nvblox parameters: ( the base paramters are the same as default)

/**:
  ros__parameters:
    # Lidar settings
    use_lidar: false
    # QoS settings
    input_qos: "SENSOR_DATA"
    # Map clearing settings
    map_clearing_radius_m: 15.0 # no map clearing if < 0.0
    map_clearing_frame_id: "base_link"
    # Rviz visualization
    slice_visualization_attachment_frame_id: "base_link"

    # Increase visualization distance (due to lidar)
    layer_visualization_exclusion_radius_m: 15.0

    static_mapper:
      # lidar integration
      lidar_projective_integrator_max_integration_distance_m: 10.0
      # esdf integrator
      esdf_slice_height: 0.16
      esdf_slice_min_height: 0.16
      esdf_slice_max_height: 0.65
      # mesh streamer
      mesh_streamer_exclusion_radius_m: 15.0

    dynamic_mapper:
      esdf_slice_height: 0.09
      esdf_slice_min_height: 0.09
      esdf_slice_max_height: 0.65

This is how I launch the nodes:

$ ros2 launch isaac_ros_occupancy_grid_localizer isaac_ros_occupancy_grid_localizer_nav2.launch.py
$ ros2 service call /trigger_grid_search_localization std_srvs/srv/Empty {}
$ ros2 launch custom_isaac nvblox.launch.py 

Hi @aravindsairam1995

Thank you for your message.

There are multiple reasons if the box isn’t an obstacle for nvblox.
You can tune some parameters:

ROS Parameter Type Default Description
<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.

In the default configuration, the value is set to <mapper_name>.esdf_slice_max_height to a value slightly higher than 0 but lower than the default configuration value. This configuration will not filter the box.

      esdf_slice_height: 0.06
      esdf_slice_min_height: 0.06
      esdf_slice_max_height: 0.65

Best,
Raffaello

Hello Raffaello, thanks for the reply. I solved it. The issues was with the ordering for the layers mentioned in the costmap plugins. The “inflation_layer” should be declared last. Now it works as intended. Here is the video.

1 Like