ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The launch file you posted will do two things:
/map
topic.costmap_2d_node
, which will output an occupancy grid for other nodes to use.However, there are still quite a few other things that need to be set up to do what you want.
First, localization. The costmap node is looking for a transform from base_footprint
frame to map
frame, not a base_footprint
topic. This transform represents the robot's best guess of where it is on the map. The process of computing a position guess is known as localization. The most widely-used and mature ROS package to do map based localization is amcl
. It uses the raw LIDAR scan, and finds the best match to the loaded map to compute the most probable position of the robot.
However, amcl
needs an odometry estimate, which needs to be generated by some other node in the system. This odometry node would integrate measured speed and yaw rate to generate a pose estimate. This pose estimate is then published as a TF transform from base_footprint
frame to odom
frame. Once set up correctly, amcl
will publish the odom
to map
transform, which will correct drift in the odometry and complete the base_footprint
to map
transform that the costmap node needs.
Next, the map layers. Below is an example YAML file for a costmap:
global_frame: /map
robot_base_frame: /base_footprint
transform_tolerance: 0.2
robot_radius: 0.6
update_frequency: 5.0
publish_frequency: 2.0
rolling_window: false
width: 100
height: 100
resolution: 0.05
origin_x: -50
origin_y: -50
plugins:
- {name: static, type: "costmap_2d::StaticLayer"}
- {name: inflation, type: "costmap_2d::InflationLayer"}
static:
unknown_cost_value: -1
lethal_cost_threshold: 100
map_topic: /map
inflation:
inflation_radius: 1.1
cost_scaling_factor: 0.2
In this example, there are two layer plugins: StaticLayer and InflationLayer. The static layer subscribes to the topic on the map_topic
parameter, and puts lethal cost on cells that correspond to a value greater than lethal_cost_threshold
in the loaded map.
The inflation layer adds cost to cells that are near lethal cost cells. This is done so that path planning algorithms that use the occupancy grid output are discouraged from planning extremely close to obstacles, but are still allowed to if absolutely necessary. The behavior of the inflation_radius
and cost_scaling_factor
parameters are nicely illustrated in the inflation layer plugin documentation linked above.
The robot_radius
is also used to pad the costmap to avoid the footprint of the robot entering lethal cost cells. The effects of the robot's footprint on cost padding is also shown in the inflation layer documentation.
I hope this helps!