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

problems in hector slam

asked 2016-05-26 21:51:18 -0500

panda gravatar image

updated 2016-06-05 21:48:03 -0500

there are 3 problem that are confirmed in my tests about hectorslam:

1, the corridor problem:hector slam think the robot is not moving when laser scan datas are almost the same at long corridor . This problem is stated clearly on ros answers, and because hector slam is not using odometer (exclude roll & pitch), the problem can not be solved

2, the quake problem: hector slam suffers when robot is during a body shake(probably when overcome an obstacle or uneven surface), it has a great possibility to messup the map(drift in yaw, the map direction is then changed) and can't recover since then. roll pitch data are introduced to solve this problem, it improves but not solved. drift happens sometimes; maybe there is some thing wrong with my system setting: imu update at 200hz, while imu_attitude_to_tf_node run at 10hz

3, the "angle too large" problem: hector slam raise "angle too large" warning when robot turns too much in a short time. however , the warning itself is unstable, I took some tests to determined how large angle will result in this, but got no pattern. and eveytime after this warning , the map drifts.

EDIT:

here are my answers for now:

1, the corridor problem is always a tricky area in laser slam, to solve this, a simple way is to replace your laser with a long range laser; a complex way is to witch using odometer in corridor, or confuse visual data;

2&3, because teamHector develop hector slam in a USAR environment, so the robot should better move as slow as their proto robot, I slow down my robot, all the two problems disappear.

any help will be appreciated

edit retag flag offensive close merge delete

Comments

Are you using the Hector slam in a ground robot or UAV

Francis Dom gravatar image Francis Dom  ( 2017-05-29 02:49:55 -0500 )edit

1 Answer

Sort by » oldest newest most voted
4

answered 2016-06-03 12:50:00 -0500

JamesWell gravatar image

updated 2016-06-03 12:52:05 -0500

I've used Hector SLAM a lot myself and all of your issues are common issues with Hector SLAM. It is important to remember what environment(video) TeamHectorDarmstadt used the robot in. The particular environment is rich in features and there are literally no long corridors, so for them, the Hector SLAM mapping and navigation algorithms were perfect.

Now using the algorithm in areas with great laser ambiguity that's another story. I'm going to try and give a short explanation to each .. question? And give you a couple of ideas to code a solution.

  1. The corridor problem occurs when one scan looks almost exactly as the next, imagine that a lot laserscanner points are registering the walls next to the robot but none of the laserscanner points ahead and behind the robot is reaching any surface (assuming the robot is travelling forward). You can actually enable odometry to use the estimated position w.r.t odometry to help the laserscanner. But make sure you have some awesome odometry, I combined odometry and a cheap IMU to first get a better odometry estimate and then enabling it in Hector SLAM, it helped some.

  2. I've never experienced this, the robot here travels on very flat surfaces. Sudden turns will ruin the mapping though.

  3. This can be resolved by tuning the parameters in the mapping_default.launch file, specifically tune your angle update and number of map resolution. I've actually run in to this problem mostly because of memory issues.. not sure why but it really helped to tune the parameters!

There are different things you can do to make HSLAM more robust one is loop closure and another is this Modeling Laser Intensities For Simultaneous Localization and Mapping awesome method which would be really cool to implement!

Hope this is useful, if all fails you could look in to mapping with vision based systems like LSD-SLAM, ORB-SLAM, RTAB etc.

edit flag offensive delete link more

Comments

thank you a lot, I have tuned the params, and figure out the robot should turn slowly when building map in few feature environment. could you give me any idea about loop closure in hector slam?

panda gravatar image panda  ( 2016-06-05 21:36:07 -0500 )edit
1

How did you "enable" your odometry in hector_slam? AFAIK hector_slam does not make use of odometry at all.

jacobperron gravatar image jacobperron  ( 2016-10-21 19:42:10 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-05-26 21:51:18 -0500

Seen: 3,712 times

Last updated: Jun 05 '16