Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Is-this-the-way-to-use-lidar-IMU-efficiently-tp7496p7515.html
As is, the command you used gives already good results. You may want to add
wait_imu_to_init to make sure odometry is initialized with IMU orientation. The bag contains GPS values (
gps_topic), we can subscribe to them in rtabmap to compare afterwards:
roslaunch rtabmap_ros rtabmap.launch \
use_sim_time:=true \
depth:=false \
subscribe_scan_cloud:=true \
frame_id:=base_link \
scan_cloud_topic:=/kitti/velo/pointcloud \
imu_topic:=/kitti/oxts/imu \
scan_cloud_max_points:=130000 \
icp_odometry:=true \
approx_sync:=false \
wait_imu_to_init:=true \
gps_topic:=/kitti/oxts/gps/fix \
args:="-d \
--RGBD/CreateOccupancyGrid false \
--Rtabmap/DetectionRate 2 \
--Odom/ScanKeyFrameThr 0.8 \
--OdomF2M/ScanMaxSize 10000 \
--OdomF2M/ScanSubtractRadius 0.5 \
--Icp/PM true \
--Icp/VoxelSize 0.5 \
--Icp/MaxTranslation 2 \
--Icp/MaxCorrespondenceDistance 1.5 \
--Icp/PMOutlierRatio 0.7 \
--Icp/Iterations 10 \
--Icp/PointToPlane false \
--Icp/PMMatcherKnn 3 \
--Icp/PMMatcherEpsilon 1 \
--Icp/Epsilon 0.0001 \
--Icp/PointToPlaneK 0 \
--Icp/PointToPlaneRadius 0 \
--Icp/CorrespondenceRatio 0.01"
To know if IMU data is added to map, you can show yellow gravity links in 3D Map view by enabling the option in Preferences dialog:


In rtabmap-databaseViewer, we can also verify that gravity values are set. We can also see the GPS values:

To better compare with GPS, the gps trajectory will appear in green in the GraphView in DatabaseViewer:

For fun, you can export the SLAM poses in GPS format so that the trajectory can be opened in
Google Earth Web. From File->Export Poses, select Google Earth (*.kml). Open KML in Google Earth (Create project, click new and import the KML file). For comparison, here the resulting map colored with normals (Edit->View Clouds...):


For the ICP parameters used most often, see this
paper. It is the same paper than the one referred in the
ouster post you already read.
Description of the parameters can be shown with:
$ rtabmap --params | grep Icp/
Param: Icp/CorrespondenceRatio = "0.1" [Ratio of matching correspondences to accept the transform.]
Param: Icp/DownsamplingStep = "1" [Downsampling step size (1=no sampling). This is done before uniform sampling.]
Param: Icp/Epsilon = "0" [Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.]
Param: Icp/Iterations = "30" [Max iterations.]
Param: Icp/MaxCorrespondenceDistance = "0.1" [Max distance for point correspondences.]
Param: Icp/MaxRotation = "0.78" [Maximum ICP rotation correction accepted (rad).]
Param: Icp/MaxTranslation = "0.2" [Maximum ICP translation correction accepted (m).]
Param: Icp/PM = "true" [Use libpointmatcher for ICP registration instead of PCL's implementation.]
Param: Icp/PMConfig = "" [Configuration file (*.yaml) used by libpointmatcher. Note that data filters set for libpointmatcher are done after filtering done by rtabmap (i.e., Icp/VoxelSize, Icp/DownsamplingStep), so make sure to disable those in rtabmap if you want to use only those from libpointmatcher. Parameters Icp/Iterations, Icp/Epsilon and Icp/MaxCorrespondenceDistance are also ignored if configuration file is set.]
Param: Icp/PMForce4DoF = "false" [Limit ICP to x, y, z and yaw DoF.]
Param: Icp/PMMatcherEpsilon = "0.0" [KDTreeMatcher/epsilon: approximation to use for the nearest-neighbor search. For convenience when configuration file is not set.]
Param: Icp/PMMatcherIntensity = "false" [KDTreeMatcher: among nearest neighbors, keep only the one with the most similar intensity. This only work with Icp/PMMatcherKnn>1.]
Param: Icp/PMMatcherKnn = "1" [KDTreeMatcher/knn: number of nearest neighbors to consider it the reference. For convenience when configuration file is not set.]
Param: Icp/PMOutlierRatio = "0.85" [TrimmedDistOutlierFilter/ratio: For convenience when configuration file is not set. For kinect-like point cloud, use 0.65.]
Param: Icp/PointToPlane = "true" [Use point to plane ICP.]
Param: Icp/PointToPlaneGroundNormalsUp = "0.0" [Invert normals on ground if they are pointing down (useful for ring-like 3D LiDARs). 0 means disabled, 1 means only normals perfectly aligned with -z axis. This is only done with 3D scans.]
Param: Icp/PointToPlaneK = "5" [Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals.]
Param: Icp/PointToPlaneLowComplexityStrategy = "1" [If structural complexity is below Icp/PointToPlaneMinComplexity: set to 0 to so that the transform is automatically rejected, set to 1 to limit ICP correction in axes with most constraints (e.g., for a corridor-like environment, the resulting transform will be limited in y and yaw, x will taken from the guess), set to 2 to accept "as is" the transform computed by PointToPoint.]
Param: Icp/PointToPlaneMinComplexity = "0.02" [Minimum structural complexity (0.0=low, 1.0=high) of the scan to do PointToPlane registration, otherwise PointToPoint registration is done instead and strategy from Icp/PointToPlaneLowComplexityStrategy is used. This check is done only when Icp/PointToPlane=true.]
Param: Icp/PointToPlaneRadius = "1.0" [Search radius to compute normals for point to plane if the cloud doesn't have already normals.]
Param: Icp/RangeMax = "0" [Maximum range filtering (0=disabled).]
Param: Icp/RangeMin = "0" [Minimum range filtering (0=disabled).]
Param: Icp/VoxelSize = "0.0" [Uniform sampling voxel size (0=disabled).]
cheers,
Mathieu