(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

How to build a Map Using Logged Data

Description: This tutorial shows you how to create a 2-D map from logged transform and laser scan data.

Tutorial Level: BEGINNER

Building a map

1. Make sure you have installed hector_slam correctly. The easiest option is to install using the package manager (example for ROS indigo):

sudo apt-get install ros-indigo-hector-slam

2. Get a bagfile to work with. For this tutorial, we will use the RoboCup 2011 Rescue Arena bagfile we recorded with a handheld mapping system. Download it to the current directory using wget:

wget https://storage.googleapis.com/google-code-archive-downloads/v2/code.google.com/tu-darmstadt-ros-pkg/Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag

You can also try the other bagfiles we provide here: http://code.google.com/p/tu-darmstadt-ros-pkg/downloads/list

3. Start the hector_slam system:

roslaunch hector_slam_launch tutorial.launch

This launch file starts the hector_mapping node as well as the hector_trajectory_server and hector_geotiff nodes needed for generating geotiff maps. Add the desired displayed types using the 'Add' button, e.g. the Map type and Point Cloud type, to visualize the desired datas.

4. Open another terminal. Type

rosbag play Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag  --clock

You should now see the mapping process in realtime in rviz.

Generating a GeoTiff map

1. To save a geotiff file at any time during the mapping process type:

rostopic pub syscommand std_msgs/String "savegeotiff"

2. By default, geotiff maps are saved to the 'hector_slam/hector_geotiff/maps' folder. You should find both a .tif file containing the image data and a .tfw file containing the georeference information there. The creation time is appended to the map base name for both files.

Troubleshooting

1. If you build hector_slam from source but find your hector mapping on Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag is different from the author's. Check if you built hector_slam in Release version to get the full performance:

catkin_make -DCMAKE_BUILD_TYPE=Release

2. hector_slam's parameters are playing roles in the mapping result as well. For example, check map_update_angle_thresh in hector_mapping/mapping_default.launch:

<param name="map_update_angle_thresh" value="0.9" />

Wiki: hector_slam/Tutorials/MappingUsingLoggedData (last edited 2020-07-21 20:26:06 by lukelu)