ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

move_base global costmap is not updated when removing an object/obstacle from the environment

asked 2021-04-07 11:52:51 -0500

updated 2021-04-08 02:53:34 -0500

Hello everyone!

I am currently working on a project using the ROS 1 navigation stack and for the past few weeks I have been struggling with this issue regarding the proper updating of move_base's global costmap when removing an obstacle from the static map. In this situation the mapping is done using the slam-toolbox package. The issue appears when switching from mapping mode to localization mode. While mapping, all the obstacles are marked in the static map and in turn the global costmap is tracking all the changes in the static map. Once I switch to localization mode, and no more changes are brought to the static map, if i remove one obstacle from the environment and my robot is close to it (the robot has 4 cameras as observation sources) I would expect for that obstacle to be cleared from the global costmap, at least as long as the cameras can see that it is not there, even though the obstacle would still be marked in the static map. I believe that the issue is related to some poor configuration of the move_base costmaps but no new combination of parameters or new configuration seems to lead me to the desired behavior.

I am attaching here the current configuration I use for my costmaps and some screenshots with the issue.

Costmaps configuration:

costmap_common.yaml

footprint: [[-0.475, -0.34], [-0.475, 0.34], [0.475, 0.34], [0.475, -0.34]]
footprint_padding: 0.02

robot_base_frame: base_footprint
update_frequency: 8.0  # Default 4.0
publish_frequency: 6.0  # Default 3.0
transform_tolerance: 0.5

resolution: 0.05

#always_send_full_costmap: true

inflation:
    inflation_radius: 1.0

#layer definitions
static:
    map_topic: /map
    subscribe_to_updates: true

virtual_walls_static_map:
    map_topic: /virtual_walls_map
    subscribe_to_updates: true
    use_maximum: true  
    track_unknown_space: false 

obstacles_laser:
    observation_sources: ultrasonics_warn ultrasonics_alert camera_1_obstacles camera_2_obstacles camera_3_obstacles camera_4_obstacles camera_1_laser camera_2_laser camera_3_laser camera_4_laser
    camera_1_laser: { data_type: LaserScan, clearing: true, marking: true, topic: /camera_1/laser_scan, obstacle_range: 5.5, raytrace_range: 6.0 }
    camera_2_laser: { data_type: LaserScan, clearing: true, marking: true, topic: /camera_2/laser_scan, obstacle_range: 5.5, raytrace_range: 6.0 }
    camera_3_laser: { data_type: LaserScan, clearing: true, marking: true, topic: /camera_3/laser_scan, obstacle_range: 5.5, raytrace_range: 6.0 }
    camera_4_laser: { data_type: LaserScan, clearing: true, marking: true, topic: /camera_4/laser_scan, obstacle_range: 5.5, raytrace_range: 6.0 }
    camera_1_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_1/obstacles_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    camera_2_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_2/obstacles_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    camera_3_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_3/obstacles_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    camera_4_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_4/obstacles_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    ultrasonics_warn: {data_type: PointCloud, clearing: false, marking: true, topic: /ultrasonic/warn_point_cloud/combined, obstacle_range: 5.5, raytrace_range: 6.0}
    ultrasonics_alert: {data_type: PointCloud, clearing: false, marking: true, topic: /ultrasonic/alert_point_cloud/combined, obstacle_range: 5.5, raytrace_range: 6.0}
    #laser: {data_type: LaserScan, clearing: true, marking: true, topic: camera/laser_scan, inf_is_valid: true, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_1_ground: {data_type: PointCloud2, clearing: false, marking: true, topic: /camera_1/ground_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_2_ground: {data_type: PointCloud2, clearing: false ...
(more)
edit retag flag offensive close merge delete

Comments

2

Have you seen #q316191?

tryan gravatar image tryan  ( 2021-04-07 19:36:04 -0500 )edit
1

Hey @tryan! Thanks for the tip...checking it now to see maybe the information there can help me!

geoporus gravatar image geoporus  ( 2021-04-08 01:55:19 -0500 )edit
1

Coming back with an update, the information in the thread linked above helped me in fixing the issue! Thanks @tryan for your help!

geoporus gravatar image geoporus  ( 2021-04-08 02:44:50 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-04-08 02:52:34 -0500

updated 2021-05-25 06:09:01 -0500

In the meantime I have managed to find the solution for my problem by using the information found in this question.

What did it for me was setting the combination method to 0 for the obstacles_laser layer and reordering the layer plugins in both the local and global costmaps. I will add the updated costmap configurations here for future reference for people that might still bump into this issue the same way that I did!

costmap_common.yaml

footprint: [[-0.475, -0.34], [-0.475, 0.34], [0.475, 0.34], [0.475, -0.34]]
footprint_padding: 0.02

robot_base_frame: sampo_base_footprint
update_frequency: 8.0  # Default 4.0
publish_frequency: 6.0  # Default 3.0
transform_tolerance: 0.5

resolution: 0.05

#always_send_full_costmap: true

inflation:
    inflation_radius: 1.0

#layer definitions
static:
    map_topic: /map
    subscribe_to_updates: false

virtual_walls_static_map:
    map_topic: /virtual_walls_map
    subscribe_to_updates: true
    use_maximum: true  
    track_unknown_space: false  

obstacles_laser:
    obstacle_range: 5.0
    raytrace_range: 5.0
    combination_method: 0
    observation_sources: ultrasonics_warn ultrasonics_alert camera_1_obstacles camera_2_obstacles camera_3_obstacles camera_4_obstacles camera_1_laser camera_2_laser camera_3_laser camera_4_laser
    camera_1_laser: {data_type: LaserScan, clearing: true, marking: true, topic: /camera_1/laser_scan}
    camera_2_laser: {data_type: LaserScan, clearing: true, marking: true, topic: /camera_2/laser_scan}
    camera_3_laser: {data_type: LaserScan, clearing: true, marking: true, topic: /camera_3/laser_scan}
    camera_4_laser: {data_type: LaserScan, clearing: true, marking: true, topic: /camera_4/laser_scan}
    camera_1_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_1/obstacles_cloud}
    camera_2_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_2/obstacles_cloud}
    camera_3_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_3/obstacles_cloud}
    camera_4_obstacles: {data_type: PointCloud2, clearing: true, marking: true, topic: /camera_4/obstacles_cloud}
    ultrasonics_warn: {data_type: PointCloud, clearing: false, marking: true, topic: /ultrasonic/warn_point_cloud/combined}
    ultrasonics_alert: {data_type: PointCloud, clearing: false, marking: true, topic: /ultrasonic/alert_point_cloud/combined}
    #laser: {data_type: LaserScan, clearing: true, marking: true, topic: camera/laser_scan, inf_is_valid: true, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_1_ground: {data_type: PointCloud2, clearing: false, marking: true, topic: /camera_1/ground_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_2_ground: {data_type: PointCloud2, clearing: false, marking: true, topic: /camera_2/ground_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_3_ground: {data_type: PointCloud2, clearing: false, marking: true, topic: /camera_3/ground_cloud, obstacle_range: 5.5, raytrace_range: 6.0}
    #camera_4_ground: {data_type: PointCloud2, clearing: false, marking: true, topic: /camera_4/ground_cloud, obstacle_range: 5.5, raytrace_range: 6.0}

costmap_local.yaml

local_costmap:
  global_frame: map  
  rolling_window: true

  static_map: false

  plugins:
    - {name: obstacles_laser,           type: "costmap_2d::ObstacleLayer"}
    - {name: virtual_walls_static_map,  type: "costmap_2d::StaticLayer"}
    - {name: inflation,                 type: "costmap_2d::InflationLayer"}

costmap_global_static.yaml

global_costmap:
  global_frame: map
  rolling_window: false
  track_unknown_space: true

  plugins:
    - {name: static,                   type: "costmap_2d::StaticLayer"}
    - {name: obstacles_laser,          type: "costmap_2d::ObstacleLayer"}
    - {name: virtual_walls_static_map, type: "costmap_2d::StaticLayer"}
    - {name: inflation,                type: "costmap_2d::InflationLayer"}

Thanks @tryan for pointing me to the thread that helped me solve the issue! Hope this answer will help others in the future!

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2021-04-07 11:52:51 -0500

Seen: 817 times

Last updated: May 25 '21