0
$\begingroup$

Greeting,

I would like to ask about setting the global costmap parameters especially the plugins. Currently in my system I enabled the following plugins- static, inflation, obstacle and voxel layers. I am wondering that the obstacle layer did not work as expected.

enter image description here

enter image description here

In the pictures, you see that there is a cart in front of the robot that is detected by laser scanner as an obstacle. However, there is no black, inflated circle around it, so I assume it did not work.

Here is the parameters. Does anyone spot any mistake here?

  global_costmap:
    ros__parameters:
      footprint_padding: 0.03
      update_frequency: 4.0
      publish_frequency: 2.0
      global_frame: map
      robot_base_frame: robot_base_footprint
      use_sim_time: False
      robot_radius: 0.3 # radius set and used, so no footprint points
      resolution: 0.05
      plugins: ["static_layer", "inflation_layer", "obstacle_layer", "voxel_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        footprint_clearing_enabled: true
        max_obstacle_height: 2.0
        combination_method: 1
        scan:
          topic: /scan
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
          raytrace_max_range: 3.0
          raytrace_min_range: 0.0
          max_obstacle_height: 2.0
          min_obstacle_height: 0.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          inf_is_valid: true
      voxel_layer:
        plugin: "nav2_costmap_2d::VoxelLayer"
        enabled: True
        footprint_clearing_enabled: true
        max_obstacle_height: 2.0
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        unknown_threshold: 15
        mark_threshold: 0
        observation_sources: pointcloud
        combination_method: 1
        pointcloud:  # no frame set, uses frame from message
          topic: /intel_realsense_r200_depth/points
          max_obstacle_height: 2.0
          min_obstacle_height: 0.0
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
          raytrace_max_range: 3.0
          raytrace_min_range: 0.0
          clearing: True
          marking: True
          data_type: "PointCloud2"
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
        enabled: True
        subscribe_to_updates: true
        transform_tolerance: 0.1
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        enabled: True
        inflation_radius: 0.3
        cost_scaling_factor: 2.7
        inflate_unknown: false
        inflate_around_unknown: true
      always_send_full_costmap: True

$\endgroup$

1 Answer 1

0
$\begingroup$

Order of the plugins matters. I believe that to be the problem here. In your params you have

plugins: ["static_layer", "inflation_layer", "obstacle_layer", "voxel_layer"]

Which means that nav2 will first check static_layer, then run inflation on that, and after that run the costmap generation for obstacle_layer. In the Rviz screenshot there are small grey pixels under the laser scan markings which means the obstacle_layer is doing things.

To inflate the obstacle_layer detections (and voxel_layer which you might want to do as well) you have to move the inflation_layer to be the last plugin.

plugins: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.