cartographer-project / cartographer_turtlebot

Provides TurtleBot integration for Cartographer.
Apache License 2.0
151 stars 96 forks source link

Parameter tuning issues for hallways #48

Closed alexbaucom17 closed 7 years ago

alexbaucom17 commented 7 years ago

I am running into some issues with very poor map quality and loop closure that I believe is likely just a parameter tuning issue. I have read through several other issues such as: this one and this one and these have helped some with the tuning.

However, I am still running into big issues with hallways becoming far too short in the map, which causes loop closure issues later on and results in maps like this: levine_4th_bad

Could anyone give me some suggestions on what parameters I should be tuning or working with to make the map better?

If it helps, I am working with a standard Kobuki Turtlebot base and a Hokuyo URG-04LX Lidar. Since I know that the odometry of the Kobuki base is pretty accurate, are there parameters I can tune to increase the reliance on the odometry and help the hallways be the correct length? From what I can tell this appears to be the main issue, but there might be other stuff going on here that I'm not aware of.

Github fork with my configuration and launch file: here Bag data I used to produce this map: here

Let me know if you need any other files in order to reproduce the issue. Thanks!

SirVer commented 7 years ago

Thank you for the detailed and easy to follow up on bug report.

I tuned a bit and left comments in the configuration file.

This got me the map below. It seems to me that your biggest issue now is that your laser mounting is not correct in the URDF. You can see that when you drive one direction, turn and drive back your room looks slightly different. For example hallways slightly bend towards one end and once you turn around, it bends in the other. This is very visible at the end of your bag where you drive back and forth into unknown space close to the starting location.

Loop closure is able to fix it now, but it means you do not get the best map possible. I suggest you check the mounting of your laser - it might be angled slightly and not perfectly flat on your robot. One or two degrees are already enough to explain this behavior

tuned

alexbaucom17 commented 7 years ago

Thank you very much for the help. I will definitely go review our URDF and see if I can fix the problem there.