Re: RTAB setup with a 3D LiDAR

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/RTAB-setup-with-a-3D-LiDAR-tp1080p1547.html

Yes, in 0.11.7 the library is updated to handle 3D laser scans. However, the ROS interface has not been totally updated.

For rtabmap node, you have now a generic point cloud input (/scan_cloud) that can be enabled with "subscribe_scan_cloud=true". There are two more parameters: "scan_cloud_normal_k" (int) to compute normals of the point cloud if not 0, "scan_cloud_max_points" the maximum points of a scan.

For odometry, the laser scan input is missing, so it will only estimate with RGB-D images (default).

You would need a node creating a depth image from rgb camera_info and Lidar data, similar to what is done in the rtabmap library. See util3d::projectCloudToCamera() (cameraTransform is the transform from lidar frame to camera optical frame) and util3d::fillProjectedCloudHoles(). Note that a node like that would be added to rtabmap_ros in the future for convenience.

So you would have these topics:
Camera: RGB image                   -> /camera/rgb/image_rect_color
Camera: RGB Camera info             -> /camera/rgb/camera_info
Lidar: Point cloud                  -> /lidar/cloud
Point Cloud Projection: Depth image -> /camera/depth_registered/image_raw

A minimal launch file:
  <launch>

  <node type="cloud_projection" ...
    <!-- inputs -->
    <param name="camera_info_topic"     value="/camera/rgb/camera_info" />
    <param name="cloud_topic"           value="/lidar/cloud"/>

    <!-- output -->
    <param name="depth_topic"           value="/camera/depth_registered/image_raw" />
  </node>

  <include file="$(find rtabmap_ros)/launch/rtabmap.launch">
    <arg name="frame_id"                value="base_link"/>
    <arg name="subscribe_scan_cloud"    value="true"/>
    <arg name="scan_cloud_max_points"   value="130000"/> <!-- Velodyne HDL-64E -->
     
    <arg name="rgb_topic"               value="/camera/rgb/image_rect_color" />
    <arg name="depth_topic"             value="/camera/depth_registered/image_raw" />
    <arg name="camera_info_topic"       value="/camera/rgb/camera_info" />
    <arg name="scan_cloud_topic"        value="/lidar/cloud"/>
   
    <!-- Icp parameters based on KITTI dataset -->
    <arg name="rtabmap_args" value="--delete_db_on_start --Reg/Strategy 1 --Icp/MaxTranslation 0 --Icp/VoxelSize 0.3 --Icp/DownsamplingStep 10 --Icp/MaxCorrespondenceDistance 0.3 --Icp/Iterations 10 Icp/Epsilon 0.01 --Icp/CorrespondenceRatio 0.1 --Icp/PointToPlane true"/>

    <!-- Default visual-only odometry, Icp ROS interface is not yet implemented-->
    <arg name="odom_args" value="--Reg/Strategy 0"/>

  </include>
</launch>

For more information about Icp parameters, see:
$ rosrun rtabmap_ros rtabmap --params | grep Icp

Some optimizations would be to downsample/voxelize the point cloud and compute normals ("scan_cloud_normal_k" can be used for that) before sending it to rtabmap node (then these parameters would be: "--Icp/VoxelSize 0 --Icp/DownsamplingStep 1").

cheers,
Mathieu