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

Generating a 2D Costmap from a map.yaml file

asked 2016-03-04 19:39:11 -0500

nicobari gravatar image

updated 2016-05-22 19:12:05 -0500

130s gravatar image

Hi, I want to generate and publish a Costmap using a user provided map file. I am having a difficult time understand costmap_2d documentation and low level simple implementation example are scarce or not available. So my launch file looks like

   <launch>
        <param name="/use_sim_time" value="true"/>
         <arg name="map_file" default="/home/chaos/turtlebotres/map.yaml"/>
         <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />

          <!-- Publishes the voxel grid to rviz for display -->
         <node pkg="costmap_2d" type="costmap_2d_markers" name="voxel_visualizer">
          <remap from="voxel_grid" to="costmap/voxel_grid"/>
         </node>

         <!-- Run the costmap node -->
          <node name="costmap_node" pkg="costmap_2d" type="costmap_2d_node" >
          <rosparam file="/home/chaos/turtlebotres/costmap2d.yaml" command="load" ns="costmap" />
         </node>
     </launch>

My costmap2d.yaml has following two parameters along with other

   global_frame: /map
   robot_base_frame: /base_footprint

I am using Turtlebot in gazebo for simulation and when I use roslaunch to launch the above launch file I am getting the following error

[ WARN] [1457141751.245245869]: Timed out waiting for transform from base_footprint to map to become available before running costmap, tf error: . canTransform returned after 0.100841 timeout was 0.1.

When I check my topic list I don't have any /base_footprint topic however I have a /tf topic and it has one frame with id base_footprint. Do I need to subscribe to /tf topic and then parse out the base_footprint and republish it on /base_footprint topic.? What is going on here and how can I solve this problem?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
7

answered 2016-03-04 23:34:52 -0500

robustify gravatar image

The launch file you posted will do two things:

  • Load the saved map and publish it on the /map topic.
  • Run the 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.

  • Run amcl to localize on the map.
  • Generate an odometry estimate
  • Configure layers for the costmap, which will populate the occupancy grid with the data from the saved map.

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!

edit flag offensive delete link more

Comments

Thanks for the excellent answer. Your explanation should be in Ros-Navigation documentation. Itmade my life easier now.

nicobari gravatar image nicobari  ( 2016-03-05 06:12:10 -0500 )edit

just a small fix that i found on main github contrib : change /map to map and same goes for base_footprint

Sachin Thakur gravatar image Sachin Thakur  ( 2021-09-08 10:56:59 -0500 )edit

Yes, definitely. This example was from long ago when leading slashes in TF frame IDs was OK. It is not anymore, so the frame IDs should definitely be map and base_footprint.

robustify gravatar image robustify  ( 2021-09-08 21:27:00 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2016-03-04 19:39:11 -0500

Seen: 6,330 times

Last updated: Mar 04 '16