Hi, We are trying to generate 3D map of typical office environment using rtabmap. We have 2 wheel robot with 360 degree 2D LiDAR, wheel encoder and two realsense D435i camera. Initially we used single realsense camera. After reducing range of camera to 2m, we have successfully generated small area maps and merged them using standalone rtabmap application in multi-session settings. But due to reduced camera range, FoV has been reduced a lot. To improve FoV, we have decided to use two realsense D435i cameras with rtabmap. Here is our launch file and db file. Launch File: https://drive.google.com/file/d/1o2SO_IMW_VoYwcYUJ90-PwVAjFSNBHl_/view?usp=sharing DB File: https://drive.google.com/file/d/1NTCxHJrsGOeKi439o1P4HrT3khyouoq_/view?usp=sharing Issues/Queries 1. Due to repetitive visual features in office environment, rtabmap 3D loop closures is failing and causing a jump in rtabmap odometry. 2. During mapping, if rover is not rotated in-place them map quality is better if compared with in-place rotatory motion. But, the disadvantage is surroundings are not properly included in generated map. 3. We tried RGBD/ProximityMaxGraphDepth value 0, 10, 30 and 50 for better loop closure. But not much improvement. 4. We have not faced this issue when mapping using single depth camera. Can you please suggest what is going wrong in mapping? Thanks, Sapana |
Administrator
|
For rgbd_sync nodelets, the approximate parameter is "approx_sync" not "approx".
You don't need to reduce the depth range before rtabmap. The 3D point cloud can be regenerated afterwards with different ranges. It is better to keep the whole range for feature matching. For the single camera setup, is it the same launch file but with rgbd_cameras set to 1? There is a wrong loop closure between node 1431 and 1202. This could have been avoided with RGBD/OptimizeMaxError=3. For better optimizations, I recommend to use Optimizer/Strategy=1 or 2. Gravity constraints are also ignored with Optimizer/Strategy=0, though here they won't be useful anyway as Reg/Force3DoF is true. Also, the odometry covariance is way too small (sigma linear=0.000999868, sigma angular=3.16228e-5). If we set RGBD/OptimizeMaxError=3, good loop closures are rejected. You can set <param name="odom_tf_linear_variance" value="0.0001"/> <param name="odom_tf_angular_variance" value="0.0003"/> As you are using a lidar, I would also enable RGBD/NeighborLinkRefining. Icp/CorrespondenceRatio can be set to default 0.1. So after editing the database you shared to set all odometry covariances as above (rtabmap-databaseViewer->Edit->Update all neighbor covariances...), here some results. rtabmap-reprocess --Optimizer/Strategy 1 --RGBD/OptimizeMaxError 3 --RGBD/NeighborLinkRefining true --Icp/CorrespondenceRatio 0.1 minimap_ProximityMaxGraphDepth_0_rerun_failed_covariance_corrected.db output.db Your odometry: With RGBD/NeighborLinkRefining=true (optimized without loop closures to see refinement effect): Then with loop closures: cheers, Mathieu |
Thanks Mathieu for quick response.
I am trying these parameters on more db files. I will get back to you. Sapana |
Free forum by Nabble | Edit this page |