Tuning Gmapping Parameters or Alternative SLAM Algorithm
We built our own robotic platform with a home made LIDAR which is composed of four Time of Flight Sensors to get range information of the environment. For odometry information we are using optical encoders. I recorded a rosbag file to save /scan /odom /tf topics which are obtained in real life setup. Unfortunately, I couldn't be able to get nice mapping performance. I tried several parameters and I digged into gmapping parameters.
Here is my best case gmapping parameters:
<param name="base_frame" value="$(arg set_base_frame)"/>
<param name="odom_frame" value="$(arg set_odom_frame)"/>
<param name="map_frame" value="$(arg set_map_frame)"/>
<param name="map_update_interval" value="2.0"/>
<param name="maxUrange" value="3.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="minimumScore" value="10"/>
<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.05"/>
<param name="angularUpdate" value="0.2"/>
<param name="temporalUpdate" value="0.5"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="100"/>
<param name="xmin" value="-10.0"/>
<param name="ymin" value="-10.0"/>
<param name="xmax" value="10.0"/>
<param name="ymax" value="10.0"/>
<param name="delta" value="0.01"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
My home made LIDAR properties:
360 Degree
64 point
1 Hz
I know that my LIDAR is not perfect, but I moved very slowly while recording rosbags. How can I improve the mapping performance? Do you know any other SLAM algorithm which could provide better performance for my case?
Here is a link to download my recorded bag file: real_data5.bag
EDIT1: Here is the gmapping result for these parameters.
EDIT2: oko_cartographer.launch file to call necessary cartographer_ros nodes with given kamu_robotu.lua (this lua file is provided below by @allenh1 : oko_cartographer.launch:
<launch>
<param name="/use_sim_time" value="true" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename kamu_robotu.lua"
output="screen">
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>
EDIT3: Here is my cartographer_ros result.
I really appreciate for your help. Thanks in advance!
Is your odometry reflecting fairly accurate changes in robot positions when you move it around ?
@spiritninja , yes odometry and LIDAR data is correct. I can see them in rviz seperately. I also measured their accuracy and they both are okay.
Note: Robot does not move immediately in the provided bag file. You need to wait a bit to see odometry change.
Playing it back locally, it seemed that the tf frames were lining up pretty well (if you increase fade time and rotate, you should be able to keep a wall in place, as I could see when your robot was rotating), and the ranges looked pretty good (especially for a home made sensor -- nice work!). I didn't use GMapping when I made a map, so I'm curious to see what yours looked like (please attach to the question!), but the map I made with Cartographer looked pretty decent (I'll upload this when I have some spare time, together with the configuration file I used).
@allenh1 , Thank you very much. I edited the post and add the link to image of gmapping result. I tried to launch cartographer, but I couldn't. I really appreciate if you can share your .launch and .lua files for cartographer
@samialperen that looks really good to me, actually. My results were not much better, and, to be frank, that's about as good as you will get with your setup and GMapping. Now, you can increase the resolution, but, if you do, you will likely get worse results due to the precision of your sensor (which, again, is extremely impressive for a homemade laser).
I would suggest using Karto SLAM. From my own experience, it gives much better results
@kosmastsk , Thank you for suggestion. I will try Karto SLAM as well. I tried to install it to ros kinetic, but I have compile errors :(