From 3211207718e477d5209091b09656a0719a0a67d8 Mon Sep 17 00:00:00 2001 From: matlabbe Date: Tue, 15 Dec 2020 10:17:18 -0500 Subject: [PATCH] Update slam_rtabmap.launch * Added **IMU support** (map is now aligned with gravity by default). * Updated **depth rectification interpolation method to NearestNeighbor** instead of Linear. This avoids a lot of noisy points in the 3D point cloud. This would also fix https://github.com/microsoft/Azure_Kinect_ROS_Driver/issues/103 at the same time. * Added **IR mode** when setting `color_enabled` to `false`. This mode can be useful when **mapping in the dark**. * Using **depth registered to RGB camera** instead of RGB registered to depth camera. This is useful for **proper texturing of the 3D mesh** when exporting the map. * Use 720P instead of 1536P so that default parameters of rtabmap can work better. Adjusted parameters between color and ir modes. * The RGB image has to be rectified, because of that, it adds black borders to RGB image. Those black borders would not affect visual odometry or loop closure detection, but it is affecting 3D point cloud reconstruction. I added this note: `When using color camera, to avoid black borders in point clouds in rtabmapviz, set ROI ratios in Preferences->3D rendering to "0.05 0.05 0.05 0.05" under Map and Odom columns.`. The black borders won't appear anymore. --- launch/slam_rtabmap.launch | 62 +++++++++++++++++++++++++++----------- 1 file changed, 45 insertions(+), 17 deletions(-) diff --git a/launch/slam_rtabmap.launch b/launch/slam_rtabmap.launch index b70e2ce3..c55fd2a1 100644 --- a/launch/slam_rtabmap.launch +++ b/launch/slam_rtabmap.launch @@ -5,6 +5,12 @@ Licensed under the MIT License. + + + + @@ -23,43 +29,65 @@ Licensed under the MIT License. - - + + - + - + - + + + + + + + - - - + + + - + - + + + + + + + + + - - - - - - - + + + + + + + + + + + +