/LVI-SAM-Easyused

LVI-SAM for easier using (更简单的使用LVI-SAM的方法)

Primary LanguageC++BSD 3-Clause "New" or "Revised" LicenseBSD-3-Clause

LVI-SAM-Easyused(中文README

This repository contains the modified code of LVI-SAM for easier using, which mainly solves the problem of ambiguous extrinsic configuration of the original LVI-SAM. Using this code, you only need to configure the extrinsic between LiDAR and IMU (T_imu_lidar), the extrinsic between Camera and IMU (T_imu_camera), and the properties of the IMU itself (which axis the IMU rotates around counterclockwise to get a positive Euler angle output), and then you can run LVI-SAM on different devices.

The test video on many datasets is available on YouTube (click below images to open) and Bilibili.

video

Update

  • The "new" branch is avaliable. We recommend you to use the "new" branch, because the LiDAR-Inertial system in the original LVI-SAM code repo uses an old version of LIO-SAM with some bugs, which have been fixed in the latest LIO-SAM code repo. At present, we have updated the latest version of LIO-SAM into LVI-SAM, so the system is more robust. You can use the following commands to download and compile the "new" branch.

    mkdir -p ~/catkin_ws/src 
    cd ~/catkin_ws/src
    git clone https://github.com/Cc19245/LVI-SAM-Easyused
    git checkout new
    cd ..
    catkin_make

Dependency

The dependency of this repo is same as the official LVI-SAM. So if you occur a compile problem, we recommend you to compile the official LVI-SAM firstly. Right now we have only tested on Ubuntu 18.04 + ROS-melodic environment.


Compile

You can use the following commands to download and compile the package.

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
git clone https://github.com/Cc19245/LVI-SAM-Easyused
cd ..
catkin_make

Note:If you want to use the no-modified code (origin LVI-SAM official code), you can change the defination in CMakeLists.txt and compile again.

################## 编译开关 compile switch##############
# -DIF_OFFICIAL=1: use origin official LVI-SAM code
# -DIF_OFFICIAL=0: use modified code of this repo
add_definitions(-DIF_OFFICIAL=0)

Params config

Sensors extrinsic config

  1. params_camera.yaml: set the VIO params, especially for T_imu_camera, which is the camera pose represented in IMU frame. It's same as VINS-Mono.
###################### extrinsic between IMU and Camera  ###########################
###################### T_IMU_Camera, Camera -> IMU       ###########################  
# R_imu_camera
extrinsicRotation: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [ 0,    0,    -1, 
               -1,     0,    0, 
                0,     1,    0]
# t_imu_camera
extrinsicTranslation: !!opencv-matrix
   rows: 3
   cols: 1
   dt: d
   data: [0.006422381632411965, 0.019939800449065116, 0.03364235163589248]
  1. params_lidar.yaml: set the LIO params, especially for T_imu_lidar, which is the lidar pose represented in IMU frame.
  ###################### extrinsic between IMU and LiDAR  ###########################
  ###################### T_IMU_LiDAR, LiDAR -> IMU       ############################
  # t_imu_lidar
  extrinsicTranslation: [0.0,   0.0,   0.0]    
  # R_imu_lidar
  extrinsicRotation: [-1,   0,    0, 
                                         0,    1,    0, 
                                         0,    0,   -1]

IMU property config

(Note: This is only the property of the IMU itself and has no relationship with its installation.)

Due to the special IMU (the Euler angle coordinate system is different from the acceleration and angular velocity coordinate system) of official dataset , you also need to set which axis the IMU rotates around counterclockwise to get a positive Euler angle output. For official sensor equipment, it is set as follows.

  ## 对绝大多数IMU来说,下面三个值分别是"+z", "+y", "+x" (for most of IMUs, the following config is "+z", "+y", "+x")
  # 绕着哪个轴逆时针转动,输出yaw角度为正(which axis the IMU rotates around counterclockwise to get a positive yaw angle)
  yawAxis: "-z"  
  # 绕着哪个轴逆时针转动,输出pitch角度为正(which axis the IMU rotates around counterclockwise to get a positive pitch angle)
  pitchAxis: "+x"    
  # 绕着哪个轴逆时针转动,输出roll角度为正(which axis the IMU rotates around counterclockwise to get a positive roll angle)
  rollAxis: "+y"    

drawing

For most of the IMUs, the Euler angle coordinate system is same as the acceleration and angular velocity coordinate system. So the above parameters should be set as follows.

  ## 对绝大多数IMU来说,下面三个值分别是"+z", "+y", "+x" (for most of IMUs, the following config is "+z", "+y", "+x")
  # 绕着哪个轴逆时针转动,输出yaw角度为正(which axis the IMU rotates around counterclockwise to get a positive yaw angle)
  yawAxis: "+z"  
  # 绕着哪个轴逆时针转动,输出pitch角度为正(which axis the IMU rotates around counterclockwise to get a positive pitch angle)
  pitchAxis: "+y"    
  # 绕着哪个轴逆时针转动,输出roll角度为正(which axis the IMU rotates around counterclockwise to get a positive roll angle)
  rollAxis: "+x"    

drawing


Run the package on different datasets

  1. Official dataset

    • Run the launch file:

      roslaunch lvi_sam run.launch
      

      Note: If you want to test the origin official LVI-SAM code (e.g. set add_definitions(-DIF_OFFICIAL=1) in CMakeLists.txt to compile), you should run launch file as following.

      roslaunch lvi_sam run_official.launch
      
    • Play existing bag files, e.g. handheld.bag:

      rosbag play handheld.bag 
      
    • Results of origin official code (up fig) and our modified code (down fig) on handheld.bag:

      drawing

      drawing

  2. M2DGR dataset

    • Run the launch file:

      roslaunch lvi_sam M2DGR.launch
      
    • Play existing bag files, e.g. gate_01.bag:

      rosbag play gate_01.bag 
      
    • Results of our modified code on gate_01.bag:

      drawing

  3. UrbanNavDataset

    • Run the launch file:

      roslaunch lvi_sam UrbanNavDataset.launch
      
    • Play existing bag files, the params we provided is for UrbanNav-HK-Data20200314. If you use other bag files of UrbanNavDataset, please check if the params need to be changed.

      rosbag play 2020-03-14-16-45-35.bag 
      
    • Results on UrbanNav-HK-Data20200314:

      drawing

  4. KITTI raw dataset

    • Run the launch file:

      roslaunch lvi_sam KITTI.launch
      
    • Play existing bag files. Please note that you must use KITTI raw dataset rather than KITTI Odometry dataset, because the latter's IMU frequency is too low. If you want to use KITTI raw dataset for LVI-SAM, you need to get rosbag files firstly. You can get it refer to LIO-SAM/config/doc/kitti2bag. Here we use KITTI_2011_09_26_drive_0084_synced raw data to get rosbag file. The transformed rosbag file can get at this link.

      rosbag play kitti_2011_09_26_drive_0084_synced.bag  
      
    • Results of our modified code on kitti_2011_09_26_drive_0084_synced.bag:

      drawing

  5. My test dataset

    • Run the launch file:

      roslaunch lvi_sam backbag.launch
      
    • Play existing bag files, e.g. backbag.bag:

      rosbag play backbag.bag 
      
    • Results of our modified code on backbag.bag:

      drawing

    • Results of our modified code on our own 0117-1525.bag (Device is different from backbag.bag, so it has another params. However, sorry for privacy issues, this data package can not open source):

      roslaunch lvi_sam ljj.launch
      rosbag play 0117-1525.bag 
      

      drawing

  6. KAIST Complex Urban Dataset

    See TODO.


TODO

  • More test on different dataset, e.g. KAIST Complex Urban Dataset. However, these datasets' lidar data have no ring information. So LVI-SAM can't run directly. If you want to run on these datasets, you need to modifidy the code to add this information refer to LeGO-LOAM.

  • We have test KAIST Complex Urban Dataset on "new" branch. We mainly made two changes:

    • We updated the latest version of LIO-SAM repo code into LVI-SAM, so the system is more robust and can run on KAIST Complex Urban Dataset successfully.
    • We generate rosbag from the origin KAIST Complex Urban Dataset, and recover the ringand time field of LiDAR pointcloud. You can using the ros package in doc/kaise-help to generate rosbags.
  • Test on KAIST Complex Urban Dataset urban26 sequence.

    • Run the launch file:

      roslaunch lvi_sam KAIST.launch
      
    • Play the generated bag files, e.g. urban26.bag:

      rosbag play urban26.bag 
      
    • Results of our modified code on urban26.bag:

      drawing

      drawing

      We can see that the trajectory has a large drift, and the loop closure doesn't be detected successfully. This may be due to the reason that the LiDAR of KAIST dataset is installed obliquely, resulting in too few valid pointclouds for registration.


Notes


Acknowledgement