Creating a map with gmapping using lidar data of a quick spinning robot
Using the lidar data of a neato vacuum cleaning robot to create a map during vacuuming was till now not possible with hector_slam. hector_slam loses very often the position of the robot during its fast spins.
So I tried to use gmapping in combination with the laser_scan_matcher instead. After a lot of tests it was able me to feed gmapping with my unusual data. Unfortunately the laser_scan_matcher calculates a position about twice as far from the map center as the real position:
Is there a trick to correct this behaviour of the scan-matcher? Here the lauch file for this demo:
<!--
Example launch file: uses laser_scan_matcher together with
slam_gmapping
-->
<launch>
#### set up data playback from bag #############################
<param name="/use_sim_time" value="true"/>
<node pkg="rosbag" type="play" name="play"
args="$(find laser_scan_matcher)/demo/vr100.bag -r 3 --delay=3 --clock"/>
#### publish an example base_link -> laser transform ###########
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser"
args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /neato_laser 100" />
#### start rviz ################################################
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find laser_scan_matcher)/demo/demo_vr100.vcg"/>
#### start the laser scan_matcher ##############################
<node pkg="laser_scan_matcher" type="laser_scan_matcher_node"
name="laser_scan_matcher_node" output="screen">
<param name="fixed_frame" value = "odom"/>
<param name="use_alpha_beta" value="true"/>
<param name="max_iterations" value="10"/>
</node>
#### start gmapping ############################################
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="map_udpate_interval" value="1.0"/>
<param name="maxUrange" value="5.0"/>
<param name="sigma" value="0.1"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.15"/>
<param name="astep" value="0.15"/>
<param name="iterations" value="1"/>
<param name="lsigma" value="0.1"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="1"/>
<param name="srr" value="0.1"/>
<param name="srt" value="0.2"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.2"/>
<param name="linearUpdate" value="1.0"/>
<param name="angularUpdate" value="0.5"/>
<param name="temporalUpdate" value="0.4"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="10"/>
<param name="xmin" value="-5.0"/>
<param name="ymin" value="-5.0"/>
<param name="xmax" value="5.0"/>
<param name="ymax" value="5.0"/>
<param name="delta" value="0.02"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.05"/>
<param name="lasamplerange" value="0.05"/>
<param name="lasamplestep" value="0.05"/>
<param name="inverted_laser" value="true"/>
</node>
</launch>
Appendix 1:
It is possible, that the neato-laser is a little bit special? It is a 360° lidar, built in right side up and rotating with 300 rpm CCW. It delivers 360 range/intensity pairs per revolution. I can't find out, if gmapping or the scan matcher have a problem with this laser and the created data header (angle increment):
There where so a lot of discussions about gmapping with inverted lasers that I don't know now if my laser is normal or inverted and if gmapping and the scan-matcher can handle the delivered data or if there are some necessary patches to do ...
Could you upload the bag file somewhere? I would love to take a closer look. I wrote the last patch regarding gmapping and inverted (and rear facing) lasers. Try checking out the last gmapping versions for your ros-version from the git-repo. I dont know if the binary already includes the patches...
Hi Ben, thank you for your interest. I uploded the first minute of the bag here: http://flasherase.ohost.de/demo.bag . Hope you can find the reason of my problem.
I will be able to look into it on wednesday. Are you using the latest version from Github? GMapping in general has problems with non-symmetrical scanners. (e.g. min_angle != -max_angle) This will lead to problems like rotation by 180 degrees in your case...
Yes, I'm using the latest version. Built it fresh last week. I wrote a mapper let me modifying the scan header and data in a wide range. It transforms topic "scan" frame "neato_laser" to topic "scan_fix" frame "laser".
Unfortunately it was not able me, to feed gmapping with this data till now because tf and laser_scan_matcher seems to be fixed to get the data from tipc "scan".
This is hector_slam mapping the uploaded test-bag. http://img19.imageshack.us/img19/6443/u5o.gif
In general before testing any SLAM algorithm, make sure that your data is correct (but noisy), i.e. test http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide#Odometry - The SLAM algorithms might seem to work "not so good" because they actually achieve to correct bad data.
I wanted not to test the algorithms (they work fine). I was interested in processing my noisy data by this algorithms. Ben_S already found a possibility to improve the stability of this process. Because my data transferred wireless I can't guarantee for gapless data streams. I'll filter them now.