In general, it should take you less than one hour to create a new map, usually about half an hour or less.
robot.launch
).slam_gmapping
package. Here's the launch file (tweaked from https://github.com/PR2/pr2_navigation/blob/hydro-devel/pr2_navigation_slam/slam_gmapping.xml):<launch> <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen"> <remap from="scan" to="base_scan"/> <param name="odom_frame" value="odom_combined"/> <param name="map_update_interval" value="30.0"/> <param name="maxUrange" value="16.0"/> <param name="sigma" value="0.05"/> <param name="kernelSize" value="1"/> <param name="lstep" value="0.05"/> <param name="astep" value="0.05"/> <param name="iterations" value="5"/> <param name="lsigma" value="0.075"/> <param name="ogain" value="3.0"/> <param name="lskip" value="0"/> <param name="srr" value="0.01"/> <param name="srt" value="0.02"/> <param name="str" value="0.01"/> <param name="stt" value="0.02"/> <param name="linearUpdate" value="0.5"/> <param name="angularUpdate" value="0.436"/> <param name="temporalUpdate" value="-1.0"/> <param name="resampleThreshold" value="0.5"/> <param name="particles" value="80"/> <param name="xmin" value="-50.0"/> <param name="ymin" value="-50.0"/> <param name="xmax" value="50.0"/> <param name="ymax" value="50.0"/> <param name="delta" value="0.0125"/> <param name="llsamplerange" value="0.01"/> <param name="llsamplestep" value="0.01"/> <param name="lasamplerange" value="0.005"/> <param name="lasamplestep" value="0.005"/> <param name="occ_thresh" value="0.65"/> </node> </launch>
The laser topic should be scan
, so we remap from PR2's base_scan
, the odometry frame is specified as a parameter (odom_combined
for PR2). Another important parameter is delta
, that's the resolution of your map, we use 0.0125. occ_thresh
is the occupied threshold from the yaml file of the generated map, we use 0.65 (it's the threshold from when a pixel is considered occupied).
roslaunch
the launch file, visualize the map in Rviz, drive the robot around carefully and slowlyrosrun map_server map_saver
. This will create map.pgm
and map.yaml
in pwd
of the terminal. The position of the origin of the resulting map in the image is specified in the map.yaml
. This is an example of the yaml
file:image: map.pgm resolution: 0.012500 origin: [-4.9, -1.9, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196
So to find out where the origin of the map is in image (.pgm file), find the coordinates in pixels:
4.9/0.0125 = 392 (so the origin of the map will be 392pixels from the left border of the image). 1.9/0.0125 = 152 (the origin is 152pixels from the bottom border)
The X axis of the rotation of the origin is the X axis of the picture, from left to right (→). The Y axis is from down to up (↑). The counting starts from top right corner. If you want to change the rotation of the origin, rotate the picture. It is recommended to upscale the image to a much higher resolution (eg 2000×2000), then rotate and align, and then scale back to the original resolution, otherwise, your resulting map will have a bad resolution.
amcl
package. Kill the gmapping
and start publishing the map and the amcl
node. Here's a launch file:<launch> <include file="$(find pr2_machine)/$(env ROBOT).machine" /> <node name="map_server" pkg="map_server" type="map_server" args="$(env PWD)/map.yaml" /> <include file="$(find pr2_navigation_global)/amcl_node.xml" /> </launch>
map.pgm
→ map-2016-06-17.pgm
. When renaming make sure you also rename the yaml
file and don't forget the map name inside the yaml
file.iai_maps
repository, iai_maps/iai_maps/maps
directoryiai_maps/iai_maps/launch/map.launch
file to point to your new awesome map.
Important: if you change the origin of the map from what it used to be previously, make sure you also adapt the transform between the origin of the furniture of the room and the map. That's usually specified in the static transform publisher of the map URDF launch file, e.g., iai_kitchen/launch/upload_kitchen.launch
or upload_kitchen_obj.launch
or similar. In addition to editing this launch file, also make sure that you tell everybody, who uses the environment models (pretty much everyone who has anything to do with the robot) that you have changed the origin.