Is this the way to use lidar & IMU efficiently?

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

Is this the way to use lidar & IMU efficiently?

Mikor
This post was updated on .
Hello,

I am using the data pulled from kitti sequence 0117 with kitti2bag and here is the information that the bag contains.

path:        kitti_2011_09_26_drive_0117_synced.bag
version:     2.0
duration:    1:08s (68s)
start:       Sep 26 2011 15:40:43.44 (1317040843.44)
end:         Sep 26 2011 15:41:51.59 (1317040911.59)
size:        3.5 GB
messages:    9240
compression: none [2641/2641 chunks]
types:       geometry_msgs/TwistStamped [98d34b0043a2093cf9d9345ab6eef12e]
             sensor_msgs/CameraInfo     [c9a58c1b0b154e0e6da7578cb991d214]
             sensor_msgs/Image          [060021388200f6f0f447d0fcd9c64743]
             sensor_msgs/Imu            [6a62c6daae103f4ff57a132d6f95cec2]
             sensor_msgs/NavSatFix      [2d3a8cd499b9b4a0249fb98fd05cfa48]
             sensor_msgs/PointCloud2    [1158d486dd51d683ce2f1be655c3c181]
             tf2_msgs/TFMessage         [94810edda583a504dfda3829e70d7eec]
topics:      /kitti/camera_color_left/camera_info    660 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_color_left/image_raw      660 msgs    : sensor_msgs/Image        
             /kitti/camera_color_right/camera_info   660 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_color_right/image_raw     660 msgs    : sensor_msgs/Image        
             /kitti/camera_gray_left/camera_info     660 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_gray_left/image_raw       660 msgs    : sensor_msgs/Image        
             /kitti/camera_gray_right/camera_info    660 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_gray_right/image_raw      660 msgs    : sensor_msgs/Image        
             /kitti/oxts/gps/fix                     660 msgs    : sensor_msgs/NavSatFix    
             /kitti/oxts/gps/vel                     660 msgs    : geometry_msgs/TwistStamped
             /kitti/oxts/imu                         660 msgs    : sensor_msgs/Imu          
             /kitti/velo/pointcloud                  660 msgs    : sensor_msgs/PointCloud2  
             /tf                                     660 msgs    : tf2_msgs/TFMessage        
             /tf_static                              660 msgs    : tf2_msgs/TFMessage


I am interested in using only the lidar + imu data and I want to learn how to do that efficiently as the title says. At this time all I do is run rtabmap.launch with the following parameters.

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:=131072  \
   icp_odometry:=true \
   approx_sync:=false \
   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"

This parameters are taken from this post . In order to add the IMU data I added the imu_topic and it seems to give slightly better results so I guess that the IMU data are included.

My questions are the following.
I think that this is the way to subscribe to the imu topics that the bag contain. Did I understand this correctly ?
Also, I need some more info about the ICP parameters, can you point me somewhere in order to do so ?

I am new to rtabmap and ros in general, every information that will help me improve my understanding will be much appreciated. Thank you in advance.
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

matlabbe
Administrator
This post was updated on .
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
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

Mikor
Salut Mathieu !

Thank you for your detailed answer and the effort that you put in for all of us.
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

Mikor
This post was updated on .
In reply to this post by matlabbe
Hey Mathieu,

I have a question for you, how did you load the data in the database viewer ?

Edit: Okay, I figured it out, you have to run rtabmap-databaseViewer and feed it with the database that is exported from the rtabmap_ros.

$ rtabmap-databaseViewer ~/.ros/rtabmap.db
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

Mikor
This post was updated on .
In reply to this post by matlabbe
Hello Mathieu,

do you have any bibliographic recommendations about how these gravity links work? Also, I can see from the rtabmap.launch file that this topic is introduced in the icp odometry node (and every odometry node in general) and in the rtabmap node but I do not quite get how this topic is used, could you describe the way it does or refer me to a paper that does?

Thanks in advance,
Anthony.
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

matlabbe
Administrator
Hi Anthony,

There is no paper on this (don't think it is publishable). IMU is used in odometry node to guess the rotation for next registration (to help better visual correspondences or better registration with ICP). It is also used to initialize the orientation of the first pose of odometry. In case of visual F2M with bundle adjustment, the IMU is also used to add attitude constraints in the g2o/gtsam graph, so that during bundle adjustment, it can help to keep attitude over time. When bundle adjustment is not used, while the odometry is started in correct orientation, it may drift over time as IMU is not reused to actually correct the orientation afterwards, just as guess. This drift would be corrected in the mapping mode afterwards in rtabmap node with the global pose graph.

For rtabmap node, the IMU is fed to graph optimisation (g2o/gtsam) as gravity factors (roll and pitch constraints). So even if odometry attitude is not estimated, it can be then corrected once in rtabmap's global graph.

Ref g2o factor: https://github.com/introlab/rtabmap/blob/master/corelib/src/optimizer/g2o/edge_se3_gravity.h
Ref gtsam factor: https://github.com/introlab/rtabmap/blob/master/corelib/src/optimizer/gtsam/GravityFactor.h

cheers,
Mathieu

Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

n.dafinski
In reply to this post by Mikor
Hello, I'm interested in using RTABMap with Lidar and IMU as well and I've got a bag of recorded topics from the two, but when I tried running it using the above commands i get the following error: "TF of received scan cloud at time 1622211363.715201s is not set, aborting rtabmap update." and after running `rosbag info` command on the rain_drive.bag i see the topics recorded are:
types:       ouster_ros/PacketMsg    [4f7b5949e76f86d01e96b0e33ba9b5e3]
             rosgraph_msgs/Log       [acffd30cd6b6de30f120938c17c593fb]
             sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
             tf2_msgs/TFMessage      [94810edda583a504dfda3829e70d7eec]
topics:      /os1_cloud_node/points      1233 msgs    : sensor_msgs/PointCloud2
             /os1_node/lidar_packets   157779 msgs    : ouster_ros/PacketMsg   
             /rosout                        7 msgs    : rosgraph_msgs/Log       
(3 connections)
             /tf_static    

in my bag file I am missing the rosout topics and the connections to tf_static, I only have a /os_cloud_node/points topic and my IMU topic, which I guess is what's causing the issues. Is there any way to get the bag to work with just those two topics or do I need to record new data?
Reply | Threaded
Open this post in threaded view
|

Re: Is this the way to use lidar & IMU efficiently?

matlabbe
Administrator
Without recording a new bag, you can republish the static TF yourself, like
rosrun tf static_transform_publisher 0 0 -0.03618 0 0 1 0 os1_sensor_base os1_sensor 100
  Ignoring the IMU, you could adjust the frame_id used by rtabmap to one of the lidar topic. However, to use IMU, you would have to have a tf linking the lidar and imu.