Skip to content

Costmap2D Obstacle Layer - Obstacles cleared when reversing away from them #5476

@zach-kudan

Description

@zach-kudan

Required Info:

  • Operating System: Ubuntu 24.04 docker container, x86 architecture
  • ROS2 Version: jazzy
  • Version or commit hash: APT binaries (dpkg-query output: os-jazzy-navigation2 1.3.7-1noble.20250624.020544)
  • Nav2 package: Costmap2D

Tuning / Configuration Goal

Have observed that when reversing away from an obstacle, as it moves outside the obstacle_max_range, the obstacle is cleared away instead of persisting.

obstacle_layer_clear_on_reverse.webm

Minimal global costmap config:

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 5.0
      global_frame: map
      robot_base_frame: base_link
      footprint: "[[0.4,0.55],[-0.4,0.55],[-0.4,-0.55],[0.4,-0.55]]"
      track_unknown_space: true
      plugins:
        - "static_layer"
        - "obstacle_layer"
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /scan
          data_type: "LaserScan"
          clearing: True
          marking: True
          obstacle_min_range: 0.0
          obstacle_max_range: 2.5
          raytrace_min_range: 0.0
          raytrace_max_range: 3.0

The map used by the static layer has resolution 0.2, full parameters:

image: map.pgm
mode: trinary
resolution: 0.2
origin: [-5.2, -18, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

What I've Tried

My current assumption is that when the raytraceFreespace takes place, it includes the cell containing the observation.

Therefore, if the observation is within the raytrace_max_range, but outside the obstacle_max_range, the cell is cleared but not marked again.

By modifying the bresenham2D function to exclude the end-point, commenting out this line, then the obstacle is no longer cleared.

(Or by decrementing the abs_da argument passed to the function)

obstacle_layer_clear_on_reverse_fix.webm

This is also fixed if obstacle_max_range is greater than raytrace_max_range, but then this creates another issue: if something is observed beyond raytrace_max_range and then moves away, it is only cleared again if the robot moves towards it and the cells move back within the clearance range.

Question

I wanted to check:

  • Is this the intended behaviour? eg: the obstacle layer should only persist obstacles it continually sees.
  • Can this be fixed by selecting different parameters, rather than modifying the code?

Metadata

Metadata

Assignees

No one assigned

    Labels

    questionFurther information is requested

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions