Re: scanning parameters
Posted by
matlabbe on
May 10, 2021; 7:20pm
URL: http://official-rtab-map-forum.206.s1.nabble.com/scanning-parameters-tp7829p7989.html
Hi Orya,
thx for the bags. I was able to scan record1.bag and record4.bag with same parameters. For record5.bag, there is too much motion blur in RGB image. Here is a comparison:
record1.bag:

record5.bag (this is where visual odometry got lost):

For record1.bag and record4.bag, here what I used:
$ roslaunch rtabmap_ros rtabmap.launch\
rtabmap_args:="\
--delete_db_on_start \
--Icp/VoxelSize 0 \
--Icp/PointToPlaneRadius 0 \
--Icp/PointToPlaneK 20 \
--Icp/CorrespondenceRatio 0.3 \
--Icp/PMOutlierRatio 0.65 \
--Icp/Epsilon 0.005 \
--Icp/PointToPlaneMinComplexity 0.02 \
--Optimizer/GravitySigma 0.3 \
--RGBD/ProximityPathMaxNeighbors 1 \
--Reg/Strategy 1 \
--RGBD/NeighborLinkRefining true \
--RGBD/LinearUpdate 0.01 \
--Optimizer/GravitySigma 0 \
--Optimizer/OptimizeMaxError 4 \
--Rtabmap/DetectionRate 2 \
--Mem/STMSize 30 " \
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 \
use_sim_time:=true
$ rosrun imu_filter_madgwick imu_filter_node\
_use_mag:=false\
_publish_tf:=false\
_world_frame:="enu"\
/imu/data_raw:=/camera/imu\
/imu/data:=/rtabmap/imu
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 \
_voxel_size:=0.005 \
_decimation:=4 \
_noise_filter_radius:=0.02 \
_noise_filter_min_neighbors:=20
$ rosbag play --clock record1.bag
or
$ rosbag play --clock record4.bag
Notice that I disabled gravity optimization (Optimizer/GravitySigma=0) because for record1.bag, the camera is looking perfectly upwards, which is causing issue with attitude estimation. rtabmap should be built with libpointmatcher support. use_sim_time should be set to false when doing live mapping with the sensor. After mapping, for convenience to export the assembled cloud with noise filtered (note that noise options have been added
today):
rtabmap-export --voxel 0.001 --noise_radius 0.005 --noise_k 10 --bin ~/.ros/rtabmap.db
Some results:





If you need a mesh:
$ rtabmap-export --voxel 0.001 --noise_radius 0.005 --noise_k 10 --bin --texture --poisson_depth 9 --color_radius 0.002 ~/.ros/rtabmap.db

cheers,
Mathieu