Skip to content

Theta star planner fails to get path when goals falls in unknown space, where tile value = NO_INFORMATION #3285

@pepisg

Description

@pepisg

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22
  • ROS2 Version:
    • Humble
  • Version or commit hash:
    • 0d86469 (latest humble branch)
    • cyclone DDS

Steps to reproduce issue

Launch the turtlebot3 simulation with these paramters:

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map
      robot_base_frame: base_link
      rolling_window: true
      width: 20
      height: 20
      robot_radius: 0.22
      resolution: 0.05
      track_unknown_space: true
      plugins: ["obstacle_layer", "inflation_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: 3.0
          raytrace_min_range: 0.0
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.55
      always_send_full_costmap: True

planner_server:
  ros__parameters:
    expected_planner_frequency: 20.0
    planner_plugins: ["GridBased"]
    GridBased:
      plugin: "nav2_theta_star_planner/ThetaStarPlanner"
      how_many_corners: 8
      w_euc_cost: 1.0
      w_traversal_cost: 2.0
      w_heuristic_cost: 1.0

They are basically the default parameters but they use a rolling global costmap without a static layer (so we can easily send the robot to an unknown tile) and the defaults for the Theta Star planner.

Then try to send the robot to a place marked as unknown in the global costmap.

Expected behavior

The theta star planner generates a path to the requested goal even if it lies on a tile whose value is NO_INFORMATION,

Actual behavior

The theta star planner fails to compute a path and shows the following error message: Either of the start or goal pose are an obstacle!

Additional information

This is likely due to the way a safe tile is defined in the theta star planner, where any cost above LETHAL_OBSTACLE (defined as 252) is treated as unsafe; howerver NO_INFORMATION tiles are set to 255, which is in fact greater than 252 but should not be considered as an obstacle.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions