Relation between laser and RGB-D

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Relation between laser and RGB-D

Bill
Hello - Our lab is beginning to experiment more with RTAB-Map on a robot, and we were wondering what role the laser play in functioning of RTAB-Map?  In the documentation, laser was used to build the grid map, and during running it appear to improve the SLAM process, e.g. builds better aligned maps.

At the moment we only have Neato's XV-11 lidar that scans at lower frame rate - are there options used to configure laser characteristics, or requirements?

Thanks!!
Reply | Threaded
Open this post in threaded view
|

Re: Relation between laser and RGB-D

matlabbe
Administrator
Hi Bill,

When you have laser scans, there are new options that come up to increase 2d map mapping precision using ICP.

A) Use laser scans to refine loop closure constraints (set "LccIcp/Type"=2):
$ rosrun rtabmap_ros rtabmap --params | grep LccIcp/Type
Param: LccIcp/Type = "0"                                   [0=No ICP, 1=ICP 3D, 2=ICP 2D]

B) Tuning parameters for laser scan matching (LccIcp2 -> Loop closure constraint ICP 2D):
$ rosrun rtabmap_ros rtabmap --params | grep Icp2
Param: LccIcp2/CorrespondenceRatio = "0.3"                 [Ratio of matching correspondences to accept the transform.]
Param: LccIcp2/Iterations = "30"                           [Max iterations.]
Param: LccIcp2/MaxCorrespondenceDistance = "0.05"          [Max distance for point correspondences.]
Param: LccIcp2/VoxelSize = "0.025"                         [Voxel size to be used for ICP computation.]

C) Activate odometry correction using the laser scans (LccIcp2 parameters above used here too):
$ rosrun rtabmap_ros rtabmap --params | grep PoseScan
Param: RGBD/PoseScanMatching = "false"                     [Laser scan matching for odometry pose correction (laser scans are required).]

D) Activate local loop closure detection (very useful when you have a laser, that it can detect closures in reverse direction):
$ rosrun rtabmap_ros rtabmap --params | grep LocalLoopDetectionSpace
Param: RGBD/LocalLoopDetectionSpace = "false"              [Detection over locations (in Working Memory) near in space.]

For the scan rate, it should be at least at the rate of RTAB-Map detection rate (which is 1 Hz be default). However, for the best synchronization of the messages in ROS, the higher the framerate, the better the laser scans will be aligned with the rgd/depth images and the odometry.

cheers,
Mathieu