ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Tuning Gmapping Parameters or Alternative SLAM Algorithm

asked 2019-04-23 06:25:39 -0500

updated 2019-04-24 10:48:20 -0500

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!

edit retag flag offensive close merge delete

Comments

Is your odometry reflecting fairly accurate changes in robot positions when you move it around ?

spiritninja gravatar image spiritninja  ( 2019-04-23 07:52:06 -0500 )edit

@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.

samialperen gravatar image samialperen  ( 2019-04-23 09:33:36 -0500 )edit

Note: Robot does not move immediately in the provided bag file. You need to wait a bit to see odometry change.

samialperen gravatar image samialperen  ( 2019-04-23 09:35:06 -0500 )edit
1

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 gravatar image allenh1  ( 2019-04-23 10:17:48 -0500 )edit

@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 gravatar image samialperen  ( 2019-04-23 13:05:06 -0500 )edit
1

@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).

allenh1 gravatar image allenh1  ( 2019-04-24 09:27:11 -0500 )edit

I would suggest using Karto SLAM. From my own experience, it gives much better results

kosmastsk gravatar image kosmastsk  ( 2019-04-24 10:37:19 -0500 )edit

@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 :(

samialperen gravatar image samialperen  ( 2019-04-24 14:39:57 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2019-04-24 09:32:22 -0500

allenh1 gravatar image

updated 2019-04-24 09:35:11 -0500

You could try Cartographer out, if you wanted. I made a decent map with this lua file.

-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
--      http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "base_link",
  published_frame = "base_link",
  odom_frame = "odom",
  provide_odom_frame = true,
  publish_frame_projected_to_2d = false,
  use_odometry = true,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 1.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)

POSE_GRAPH.optimization_problem.huber_scale = 1e2

return options

I ran it with these settings.

rosrun cartographer_ros cartographer_node -configuration_directory [wherever you put it] -configuration_basename realoguz.lua

And to get the grid map, run the below.

rosrun cartographer_ros cartographer_occupancy_grid_node

I got this map (it's small because the area is rather small).

image description

edit flag offensive delete link more

Comments

@allenh1 Thank you very much for providing the lua file. I saved the lua file you provided named as kamu_robotu.lua. Then I used oko_cartographer.launch, which I added into original post. I also added my mapping result, but it seems my mapping result is not as good as yours. Normally, there are two objects in the map one of them is square and the other one is cylinder. Our aim is to detect them as perfect as possible. Do you have any other suggestion? What should I do to improve the results. I really tried hard to tune gmapping, but I failed to detect objects nicely. I really appreciate for your help!

samialperen gravatar image samialperen  ( 2019-04-24 10:43:07 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-04-23 06:25:39 -0500

Seen: 1,637 times

Last updated: Apr 24 '19