Greetings,
I am running slam_gmapping ( gmapping ) in PioneerAT with Sick LMS200 on ROS Diamondback. I am using slam_gmapping_pr2.launch from gmapping package. Following picture shows the result. TF defined is also visible in image.
The map is curved on straight corridors. Parallel corridors are merged. A small circular move (loop ~ radius 3meters, at center) is not detected. One corridor has come twice (parallel,joined) due to some problem.
I tried changing the launch file and used following:
<launch>
<param name="use_sim_time" value="true"/>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<!-- <remap from="scan" to="scan"/>-->
<param name="odom_frame" value="/RosAria/pose"/>
<param name="map_udpate_interval" value="2.0"/>
<param name="maxUrange" value="12.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.1"/>
<param name="srt" value="0.2"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.2"/>
<param name="linearUpdate" value="0.5"/>
<param name="angularUpdate" value="0.5"/>
<param name="temporalUpdate" value="3.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="30"/>
<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.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
</node>
</launch>
This resulted in even worse map shown in picture below:

Scan Matching Failed, using odometry. Likelihood=-90.753
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-297.351
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-822.941
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-1200
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-1200
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-987.667
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-1200
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-257.575
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-1200
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-216.73
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Scan Matching Failed, using odometry. Likelihood=-1008.48
lp:18.5471 -20.6458 -1.92343
op:18.1182 -5.70109 1.08139
Above are some of console output which may be of help in diagonising the problem.
The bag file can be found here: http://www.mediafire.com/?4ftzaenx28ilfow
I am not able to make out what wrong I am doing?
Is there any checklist page which help on checking out potential configuration issues?
It fares really badly on in place rotations. in-place-rotations are not so fast. What can be done to improve that.
Why straight corridors are coming curved? any ideas?
Any help page or help link for similar problem? I tried searching forum but nothing much could be found.
Laser mounted on pioneer, looks down. It is not parallel to ground. Could it be a problem?
thank you.
If I recall correctly, gmapping doesn't support mapping with a tilted laser scanner. It should be perpendicular to the ground or otherwise not see something like ground or ceiling every scan, otherwise the scan matching will not work properly.
If you really want to keep your laser tilted, you'll need to do something to filter the ground plane out of the scans.
From my experience, changing the linearUpdate parameter and the angularUpdate parameter to a lower value while increasing the number of particles (100 is the usual amount for me) provides better performance [as long as your computer can process it].
Asked: 2012-04-02 15:04:25 -0500
Seen: 394 times
Last updated: Apr 02 '12
Why TF tranformations from odometry to robot_base in P3DX devide by 1000?
Gmapping doesn't build a clear map
Corrected Odometry from GMapping / Karto?
Issue with setting tf in gmapping
How to change fake laser scan direction of rotation
Navigation Stack with gmapping
2D SLAM with gmapping and openni_kinect
ROS Answers is licensed under Creative Commons Attribution 3.0 Content on this site is licensed under a Creative Commons Attribution Share Alike 3.0 license.