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

How to prevent hector_mapping from losing the position of the robot

asked 2013-09-12 01:46:23 -0600

FlashErase gravatar image

updated 2014-04-20 14:09:24 -0600

ngrennan gravatar image

I'm using a VR100 vacuum cleaning robot (aka neato) with a 360° lidar (1 distance measure per degree, five revolutions per second) to create a map with hector_slam. Unfortunately the mapper often loses the estimated position of the robot and starts a new mapping process on another place of the map and with an different angle: http://img27.imageshack.us/img27/2466/ahor.png In the log of the roscore also often appears the output "SearchDir angle change too large". This is comprehensible because the cleaner sometimes rotates almost quick around itself. Is there a possibility in configuration to make hector_slam resistant against such kind of movement and to prevent the frequently restart of mapping on a new position?

Appendix 1: Meanwhile I made some experiments with configuration parameters. Decreasing the map_update_angle_tresh(old) to 0.01 and degrading the map_resolution to 0.075 causes the mapper to glitch not so often. But the created map looks a litte poor: http://img845.imageshack.us/img845/9906/a4nc.png

Appendix 2: Now I've used a bag with double filtered data. Once out of the driver and second time with rosbag filter. However hector_slam can't create a map out of this data without hickups. I created two partial maps (~ 20% of the whole bag): http://img818.imageshack.us/img818/6504/hgxj.png and http://img43.imageshack.us/img43/9436/tqna.png A better resolution than 0.65 causes a wild hopping during creation of map. I'm afraid that hector_slam in general can't handle this kind of data. Any other hints or a tipp how to create the tf-topic to test these data with gmapping?

Appendix 3 to the edit of jodafos answer
So I'll find out how to start an odometry calculator to create this data for gmapping.
Increasing the value of "map_multi_res_levels" increases the problems. The map with level "2" I posted above: http://img818.imageshack.us/img818/6504/hgxj.png . This is the map with level "3": http://img94.imageshack.us/img94/8259/fqo.png , with level "4": http://img22.imageshack.us/img22/7415/rzrv.png and with level "5": http://img577.imageshack.us/img577/528/4mmg.png . All other settings and the used bagfile are identical for all tries.

edit retag flag offensive close merge delete

Comments

Hi FlashErase, have you resolved this problem by any chance? I am having the same map-jumping problem with 2 of my hokuyo lidars that I use to get 360 degree view.

kost9 gravatar image kost9  ( 2014-10-20 00:55:12 -0600 )edit

No, unfortunately there was no complete solution for this problem. But Ben_S posted some adjustments for the configuration here: http://answers.ros.org/question/79386... This decreased the number of origin jumps.

FlashErase gravatar image FlashErase  ( 2014-10-20 02:54:22 -0600 )edit

2 Answers

Sort by » oldest newest most voted
6

answered 2013-09-12 02:44:22 -0600

jodafo gravatar image

updated 2013-09-13 06:50:43 -0600

Hello again,

to my knowledge the hector devs use 40hz long range high precision lidars, so you might indeed need to change a couple of things. Since they actually have 8 callbacks where you have one i'd change the max searchdir of 0.2 to something higher (maybe to 0.2*8) in lines 209 to 215 of https://github.com/tu-darmstadt-ros-pkg/hector_slam/blob/master/hector_mapping/include/hector_slam_lib/matcher/ScanMatcher.h You can also increase the number of iterations, however this will most likely not help because if it gets stuck in a local minima, well, its stuck.

Also I guess that the lidar on your vacuum cleaner is not that precise, so you might have to live with imperfect results. If increaseng the searchdir limit doesn't yield acceptable results you could try gmapping which uses a particle filter which can deal better with the problem you are facing than a "simple" scanmatcher. Additionally, once you have a good map (gained for example by not doing sharp turns), you could also just localize your robot without mapping, since your map will be mostly static. To do so you can either use amcl, or see if hector slam can work with given maps. around half a year ago that was not possible, but maybe someone added that feature. if not you can of course also do so yourself, the hector slam code is well written and understandable.

@appendix1: well, seeing that you have a 360deg lidar i wouldn't decrease the threshold for the angular map update trigger ;). On the contrary, my intuition would be that turning shouldn't trigger updating the map at all. That decreasing the map resolution on the other hand helps is intuitive since it sort of reduces the impact of noisy readings. You could try increasing the number maps used in parallel, i.e. increase 2 in

<param name="map_multi_res_levels" value="2" />

what this does is performing the registration on courser grained maps in parallel to your original map resolution. The purpose is preventing to get stuck in local minimas, which is whats happening in your case.

@appendix2: Hmm, I never used hector slam with quick rotations, so I don't know from experience how well it can cope with those. Concerning "gmapping requires tf": I think you got your vocabulary wrong :). Tf stands from transform, and in ros this refers to a description/link between frames. Thus you don't just need tf for gmapping but also for hector slam. you should already have something like world/map->odom->base_footprint->base_stabilized->base_link->laser_link. What you do "need" for gmapping is odometry, which is /rpm i guess? Even if not, you can use a scanmatcher in place of wheel odometry.

@comments: The issue with higher (integer) values for multi_res_level making no map appear is pretty weird. Have no clue what that is about. You did just set it to 3/4/5 and didn't go all-out here right? It's a shame though ... (more)

edit flag offensive delete link more

Comments

Hi jodafo, my hero. Thank you for the hint. I'll try this tomorrow. I made an appendix to my question.

FlashErase gravatar image FlashErase  ( 2013-09-12 03:10:07 -0600 )edit

Increasing the max searchdir to 1.2 takes no effect. Two additional "return false" in case of this range error without updating the estimated position prevents big jumps but the map is always creepy. I cant get a good static map. To your appendix: Increasing the multi_res_level causes a blank map.

FlashErase gravatar image FlashErase  ( 2013-09-12 06:46:53 -0600 )edit

gmapping requires tf-data. My driver only provides /scan and /rmps. If there is an interest I can send a bag with the problematic data. Because I don't control the robot manual I can only record data durring it's cleaning process with a lot of fast turns and spins.

FlashErase gravatar image FlashErase  ( 2013-09-12 06:47:57 -0600 )edit

Watching the raw lidar data in the bag I found out, that there were some short interruptions in the bluetooth connection. So, at first, I have to modify the neato-driver to publish only valid data. Hope this will help against some of the hickups of the mapper.

FlashErase gravatar image FlashErase  ( 2013-09-12 10:35:59 -0600 )edit
1

answered 2013-09-12 03:20:02 -0600

I never tried it with the Neato LIDAR (and being on a DRC Team working on a Atlas robot don´t have spare time to look into improvements currently), but there are people that seem to get good results with the neato lidar:

  1. Related Q/A
  2. Video on YouTube

So it seems that at least for some scenarios, it can work. There´s some parameters like the grid resolution that could be tuned. Also, there is no check for giant pose jumps in hector_mapping currently (as these do not appear to happen for our use cases), but there definitely is room for improvement there. Means you would have to dig into the code though.

edit flag offensive delete link more

Comments

Thanks for your hints. in the video the roboot only turns slowly, so tha mapping has no problem. I cant prevent my robot from fast turns and spins. Because the driver only provides /scan and /rpms the described problems with concurrent tf-data does not happen here.

FlashErase gravatar image FlashErase  ( 2013-09-12 06:54:17 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2013-09-12 01:46:23 -0600

Seen: 5,708 times

Last updated: Sep 13 '13