Closed zyh0333 closed 2 years ago
the double wall problem is something I've seen too especially in simulation. It seems to get better if I set the rate of the camera from 30fps to 60ps which, however, is not always possible in the real world.
@zyh0333 If you are using L515 in RGB-D mode, odomety drift is high because RGB and depth are not perfectly synchronized, RGB is quite blurry and with small field of view. This is the first example like with D435i: 1) RGB-D mode
$ roslaunch rtabmap_ros rtabmap.launch \
rtabmap_args:="--delete_db_on_start --Optimizer/GravitySigma 0.3" \
depth_topic:=/camera/aligned_depth_to_color/image_raw \
rgb_topic:=/camera/color/image_raw \
camera_info_topic:=/camera/color/camera_info \
approx_sync:=false \
wait_imu_to_init:=true \
imu_topic:=/rtabmap/imu
2) There is a Depth-ICP mode (without RGB), that will work only if there is enough geometry. This is explained in this post: http://official-rtab-map-forum.206.s1.nabble.com/Kinect-For-Azure-L515-ICP-lighting-invariant-mapping-td7187.html, here is the example:
$ rosrun nodelet nodelet standalone rtabmap_ros/point_cloud_xyz \
_approx_sync:=false \
/depth/image:=/camera/depth/image_rect_raw \
/depth/camera_info:=/camera/depth/camera_info \
_decimation:=4
$ roslaunch rtabmap_ros rtabmap.launch\
rtabmap_args:="\
--delete_db_on_start \
--Icp/VoxelSize 0.05 \
--Icp/PointToPlaneRadius 0 \
--Icp/PointToPlaneK 20 \
--Icp/CorrespondenceRatio 0.2 \
--Icp/PMOutlierRatio 0.65 \
--Icp/Epsilon 0.005 \
--Icp/PointToPlaneMinComplexity 0 \
--Odom/ScanKeyFrameThr 0.7 \
--OdomF2M/ScanMaxSize 15000 \
--Optimizer/GravitySigma 0.3 \
--RGBD/ProximityPathMaxNeighbors 1 \
--Reg/Strategy 1" \
icp_odometry:=true \
scan_cloud_topic:=/cloud \
subscribe_scan_cloud:=true \
depth_topic:=/camera/aligned_depth_to_color/image_raw \
rgb_topic:=/camera/color/image_raw \
camera_info_topic:=/camera/color/camera_info \
approx_sync:=false \
wait_imu_to_init:=true \
imu_topic:=/rtabmap/imu
Note also that L515 is quite sensitive to external sunlight, this will affect also odometry. For the double surfaces, if odometry is drifting a lot, loop closure detection can reduce the error, but won't perfectly eliminate perfectly the double surfaces.
@matlabbe Thank you for your reply! I've tried D435i and it can get much better result, maybe the poor quality of 3D reconstruction is because L515 itself... But due to the testing environment, our lab wants to change to L515 + T265, let L515 get external odometry from T265. I'll close this issue and start another one~
I am new to rtabmap...
My camera is Realsense L515, ros version is melodic. I follow the tutorial of "RGB-D Handheld Mapping", every time before I export the cloud file, I post-processing it, and export it as organized map with regeneration. and I have the following issues: I find this map is a little bit twisted...
This one repeated the same thing for twice...
This one seems better, but from the up view, there's three layers of walls (not a big deal compared with former two problems)
Every time I ran the rtabmap_ros with default commands same as http://wiki.ros.org/rtabmap_ros/Tutorials/HandHeldMapping and I added some more arguments when launching:
there's also some other maps, I may also made same mistakes for these maps