Previously (i.e. pre-hydro) it has been possible to have a global_costmap
that takes in sensor data as well as the static map from the map_server
. If I remember correctly, this allowed to have the sensor data "clear" data of the static map to plan through, e.g., doors that had been closed during mapping.
With the current system, I haven't been able to reproduce this behaviour.
Even stranger: as soon as I add an obstacle_layer
to the global_costmap
(even without receiving any data on the configured sensor), the global_costmap
simply doesn't receive any data at all. I.e. the robot plans the direct path to the goal, through whatever is set in the map_server
.
I'm not sure if this is a configuration issue on my end, or if this is really something that is not possible with the layered costmap approach. Even if the "clearing" behaviour is hard to realize, my current system should end up with an "overlay" of the single layers. I.e. the static_layer
should still show. This is also how I understand this paper by @David Lu.
I created a minimal example (see below). This example is stand-alone and doesn't depend on Gazebo or a robot.
Any hint to where I have made a mistake would be highly appreciated!
Results
The trick was really the combination_method
parameter in combination with the track_unknown_space
parameter.
(Note: I used some fake laser which simply published a circle with radius 3m at 1° angular resolution. Also, the images only show the robot_footprint
and the resulting global_costmap
)
- I: The behaviour I experienced.
static_layer
gets completely overwritten byobstacle_layer
- II: behaviour I wanted.
static_layer
gets only overwritten byobstacle_layer
where there are actually some measurements (see the light blue traces along the rays. It is not free space, but you see the effect). If you plan a path, it tries to follow any observations, if possible, and only cross unkown space if required (leads to some zigzag behaviour along the rays of the scans) - III: default behaviour: obstacles present in either
static_layer
orobstacle_layer
are used - IV: afair, same as III for the costmap, though planning will happen as in II.
Below some pictures of the different combinations:
I: combination_method: 0
, track_unkown_space: false
II: combination_method: 0
, track_unkown_space: true
III: combination_method: 1
, track_unkown_space: false
IV: combination_method: 1
, track_unkown_space: true
Minimal Example
Put the following files in your home. You'll need a map to pass to the map_server
as well as rviz
with a proper configuration (map
, global_costmap
, maybe robot_footprint
).
Play around with using the obstacle_layer
in the global_costmap
to see the different results.
movebase.launch
<?xml version="1.0"?>
<launch>
<!-- delete old parameters -->
<rosparam command="delete" param="/move_base"/>
<node name="map_server" pkg="map_server" type="map_server" args="/PATH/TO/MAP"/>
<node name="map_to_odom" pkg="tf" type="static_transform_publisher" args="2 0 0 0 0 0 map odom 10"/>
<node name="odom_to_base_link" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 odom base_link 10"/>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="controller_frequency" value="10"/>
<!-- Use the dwa local planner for the PR2 -->
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<!-- Set the global_planner -->
<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<rosparam file="./local_costmap_params.yaml" command="load" ns="local_costmap"/>
<rosparam file="./global_costmap_params.yaml" command="load" ns="global_costmap"/>
</node>
</launch>
global_costmap_params.yaml
global_frame: map # default: "/map"
robot_base_frame: base_link # default: "base_link"
update_frequency: 4.0 # default: 5.0
publish_frequency: 1.0 # default: 0.0
rolling_window: false # default: false
static_map: true # default: true
transform_tolerance: 0.6 # default: 0.2
footprint: [[0.35,0.205],[0.42,0],[0.35,-0.205],[-0.225,-0.205],[-0.225,0.205]]
footprint_padding: 0.01 # default 0.01
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
static_layer:
unknown_cost_value: 0 # default: 0
lethal_cost_threshold: 100 # default: 100
map_topic: map # default: "map"
obstacle_layer:
combination_method: 0
observation_sources: laser_scan
map_type: costmap
unknown_threshold: 2 # default: ~<name>/z_voxels
mark_threshold: 0 # default: 0
publish_voxel_map: true
obstacle_range: 10.0 # default: 2.5
raytrace_range: 10.0 # default: 3.0
laser_scan:
sensor_frame: laser # default: ""
topic: /scan # default: source_name
data_type: LaserScan # default: "PointCloud"
marking: true # default: true
clearing: true # default: false
inflation_layer:
inflation_radius: 0.45 # default: 0.55
cost_scaling_factor: 8.01 # default: 10.0
local_costmap_params.yaml
global_frame: map # default: "/map" -> WARNING: Default value has a "/" in front of the frame-name
robot_base_frame: base_link # default: "base_link"
update_frequency: 4.0 # default: 5.0
publish_frequency: 2.0 # default: 0.0
rolling_window: true # default: false
static_map: false # default: true
width: 5.0 # default: 10
height: 5.0 # default: 10
resolution: 0.05 # default: 0.05
origin_x: 0.0 # default: 0.0
origin_y: 0.0 # default: 0.0
transform_tolerance: 0.6 # default: 0.2
footprint: [[0.35,0.205],[0.42,0],[0.35,-0.205],[-0.225,-0.205],[-0.225,0.205]]
footprint_padding: 0.01 # default 0.01
plugins:
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
static_layer:
unknown_cost_value: 0 # default: 0
lethal_cost_threshold: 100 # default: 100
map_topic: map # default: "map"
obstacle_layer:
combination_method: 0
observation_sources: laser_scan
map_type: costmap
unknown_threshold: 2 # default: ~<name>/z_voxels
mark_threshold: 0 # default: 0
publish_voxel_map: true
obstacle_range: 10.0 # default: 2.5
raytrace_range: 10.0 # default: 3.0
laser_scan:
sensor_frame: laser # default: ""
topic: /scan # default: source_name
data_type: LaserScan # default: "PointCloud"
marking: true # default: true
clearing: true # default: false
inflation_layer:
inflation_radius: 0.45 # default: 0.55
cost_scaling_factor: 8.01 # default: 10.0
Originally posted by mgruhler on ROS Answers with karma: 12390 on 2019-02-20
Post score: 6