Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Global loop closure optimization breaks the map #141

Closed
esonetec opened this issue Nov 23, 2016 · 2 comments
Closed

Global loop closure optimization breaks the map #141

esonetec opened this issue Nov 23, 2016 · 2 comments
Assignees
Labels

Comments

@esonetec
Copy link

Hello guys,

i am testing cartographer now since few weeks and have occasionally the problem, that the global loop closure optimization makes the almost perfect map much worse.

See this example:
image
(before optimization)

image
(after optimization)

I am running cartographer with a 2d lidar (40hz, <60m range) and an imu (40hz) on ubuntu 14.04, ros indigo. I use the latest sources of cartographer.

You can find here an example bag files to reproduce the issue i am describing: https://drive.google.com/file/d/0B9jUq7WkDIxbOE95cHhJVGlPMFU/view
The lua configuration i use:
https://drive.google.com/open?id=0B9jUq7WkDIxbbkVXRjBYanNRT00
Launch file:
https://drive.google.com/open?id=0B9jUq7WkDIxbdkRyaGxDbU5lTnc

I read in #127 the advice increasing the huber_scale and min_score. I played around with different values and in many cases the quality of the map is getting worse.

Is the cause for worse maps in my case the same reasons as described in #127? Are their any other parameters one can/should tune for getting the global optimization produce more "stable" results?

Thanks in advance!

@damonkohler damonkohler self-assigned this Nov 25, 2016
@damonkohler
Copy link
Contributor

First, sorry for the delay.

I experimented with your bag and found some settings that work reasonably well.

The generally guidance is that, as the sensor FOV is decreases, reliance on local SLAM must increase. Since your laser scanner is only 180 degrees, I increased the number of scans per submap, increased the minimum score required for loop closure detection, and decreased the Huber scale:

TRAJECTORY_BUILDER_2D.submaps.num_laser_fans = 270

SPARSE_POSE_GRAPH.optimize_every_n_scans = 270
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e1
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.8

Enabling correlative scan matching also helps a bit.

image

I also noticed that the transformation for your IMU seems incorrect. It seems to be oriented z-down and your static transform for it is looks to be around yaw, not pitch or roll.

Lastly, setting the variance of odometry has no effect since you have no odometry. Setting it to 0 in any case would be a bad idea as well.

@esonetec
Copy link
Author

esonetec commented Dec 6, 2016

Hey damonkohler,

thanks a lot for looking into it! I can confirm that the map is now looking as good as in your screenshot.

You are right that the TF for the IMU is incorrect. I had put the wrong orientation data in the launch file accidently while extracting it from our code.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

3 participants