Hi again, Mathieu!
This time, I am asking for advise on parameter tunning. I understand there is no exact answer for parameter tunning. I have spent long time tunning these parameters and my final set up still does not seem too good. Below I have listed parameters that I have changed from default value. Reg\Force3DoF = false → true General\cloudFilteringRadius = 0.10000000000000001 → 0.11 General\cloudNoiseMinNeighbors = 5 (stay) Vis\MaxDepth = 0 → 4 Vis\MinDepth = 0 Vis\MinInliers = 3 → 35 Vis\InlierDistance = 0.1 → 0.05 Kp\MaxDepth = 0 → 4 Kp\MinDepth = 0 → 0.4 RGBD\AngularUpdate = 0.1 → 0.01 RGBD\LinearUpdate = 0.1 → 0.01 RGBD\CreateOccupancyGrid = false → true Icp\CorrespondenceRatio = 0.2 → 0.5 SURF\HessianThreshold = 500 → 60 Mem\RehearsalSimilarity = 0.6 → 0.2 Grid\DepthMax = 0.0 → 5.0 Grid\DepthMin = 0.0 → 0.3 Grid\RayTracing = false →true I am asking for little advise what to tune further more. (especially the walls does not align perfectly). Here I am attaching files that I have used for mapping. - rosbag file: google drive link -> https://drive.google.com/open?id=1_9khZtIrsbEZHp1itsF2f0mugUJaLEBi - rtabmap launch file: rtabmap.launch - rtabmap.ini file: rtabmap.ini Cheers, |
Administrator
|
Hi,
you may share the resulting database (176 MB) before the bag (22GB) for convenience as the problems I am seeing could be detected with only the database. 1) RGB and depth images are poorly synchronized and registered. To deal with registration, a re-calibration may be required. For synchronization, maybe reduce the rotation speed of the robot. This can affect cloud alignments and also loop closure accuracy. Two examples: Note how the depth image doesn't match perfectly with the RGB image (rtabmap-databaseViewer used for visualization): In rotation, the depth corresponds even less to RGB image: 2) For the double walls, as odometry seems quite accurate, maybe it is the TF between robot base frame and camera frame that is not accurate enough (or the camera real position doesn't match with TF base_footprint->camera_link). For example, the following screenshot shows that the height of the camera doesn't look high enough in TF, causing the cloud to be under the ground (the gray line is the grid at z=0). If there is also a wrong TF offset in along x or y axis, this can be a problem to correctly transform clouds into robot base frame to match exactly the odometry poses. 3) A loop closure can only be found at the end of the run, so quality of the map is mostly caused by the problems above. The depth image of the camera may have also some distortions over 3-4 meters. However, the map is relatively good even with these issues (i.e., it is not a rtabmap parameters issue a this point). A better calibration, more accurate TF, and maybe make the robot do some 360 [slow] rotation when it passes again over precious paths may help to find more loop closures. cheers, Mathieu |
Free forum by Nabble | Edit this page |