Persistent local scan matching ignored error for Lidar + robot + Odometry + RGBD mapping

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Persistent local scan matching ignored error for Lidar + robot + Odometry + RGBD mapping

alexr
Hi Mathieu,

I am constantly getting the below error when mapping indoors in well structured environments

Ignoring local loop closure with 205 because resulting transform is to large!?
and
Rtabmap.cpp:1831::process() Rejected loop closure 121 -> 137: Not enough inliers 16/20 (matches=34) between 121 and 137
  for many nodes.

I have recently switched the Lidar on the robot from Hokuyo short range to a long range SICK lidar (20 m, 50Hz). When running Gmapping with the robot I find no trouble. But with RTABMAP with the default demo_robot_mapping.launch file the map gets corrupted. I am using the following parameters. I believe that using a long range scanner with high update rate should produce better scan matching for ICP. I am not sure what parameters are wrong.

 <!-- RTAB-Map's parameters: do "rosrun rtabmap rtabmap (double-dash)params" to see the list of available parameters. -->
	  <param name="RGBD/NeighborLinkRefining" type="string" value="true"/>  <!-- Do odometry correction with consecutive laser scans -->
	  <param name="RGBD/ProximityBySpace"     type="string" value="true"/>  <!-- Local loop closure detection (using estimated position) with locations in WM -->
	  <param name="RGBD/ProximityByTime"      type="string" value="false"/> <!-- Local loop closure detection with locations in STM -->
	  <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/> <!-- Do also proximity detection by space by merging close scans together. -->
	  <param name="Reg/Strategy"              type="string" value="1"/>     <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
	  <param name="Vis/InlierDistance"        type="string" value="0.1"/>   <!-- 3D visual words correspondence distance -->
	  <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/> <!-- Optimize graph from initial node so /map -> /odom transform will be generated -->
	  <param name="Reg/Force3DoF"             type="string" value="true"/>
	  <param name="Grid/FromDepth"            type="string" value="false"/>

How can I improve the mapping results. With Hokuyo I never had this trouble. Also, when I change  
<param name="RGBD/LocalLoopDetectionTime" type="string" value="false"/> 
 to
true
 the results are slightly better. But the grid map does not look so good. You can see in the map there are so many areas where the occupancy has not been filled for obstacles.

Results with RGBD/LocalLoopDetectionTime = True
 


Results with RGBD/LocalLoopDetectionTime = False


Can you suggest something to improve the results. My final goal is to do multi-mapping session for such long environments.

Thanks
------ Alex
Reply | Threaded
Open this post in threaded view
|

Re: Persistent local scan matching ignored error for Lidar + robot + Odometry + RGBD mapping

matlabbe
Administrator
Do you have the database without "RGBD/LocalLoopDetectionTime" to share? It seems that is an optimization problem, in particular g2o can be sensitive to covariance set by odometry. Try with TORO or GTSAM: "Optimizer/Strategy" to 0 or 2 respectively. I don't recommend using "RGBD/LocalLoopDetectionTime=true", as it generally doesn't add very much accuracy comparing for as many links added (which increases quite a lot graph optimization time).

If you are going to do multi-session mapping, I also don't recommend g2o as it optimizes poorly multiple maps. GTSAM is the better, however, with many maps, it can happen that GTSAM returns no solution, so loop closures are rejected. TORO is the most stable between the three, though not giving as good optimizations, it will always find a solution in multi-session mapping. A small issue with TORO is when the map is getting very big, it puts sometimes all errors in one link even if the new loop closure is good, thus "RGBD/OptimizeMaxError" should be set to 0 to avoid rejecting good loop closures.  

For the sensor, the map should be better with a 20 m than a 4 m. The robot mapping demo (video) uses a 30 meters UTM-30LX, launch file here.

cheers,
Mathieu