This repository contains modified code of LVI-SAM for easier using. The test video on many datasets is available on YouTube (click below images to open) and Bilibili.
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_camera.yaml
: set the VIO params, especially for T_imu_camera. 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]
params_lidar.yaml
: set the LIO params, especially for T_imu_lidar.
###################### 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]
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 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"
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"
-
-
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:
-
-
-
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:
-
-
-
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:
-
-
-
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:
-
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
-
- More test on different dataset, e.g. KAIST. 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.
- This code just modified the extrinsic config of LVI-SAM for easier using. Its purpose is to allow you to adapt to other datasets and your own devices faster. So it does NOT modify the algorithm part of LVI-SAM.
- If you want to know what changes I made and why they make sense, you can refer to my blog: LVI-SAM坐标系外参分析与代码修改,以适配各种数据集.
- I made a Chinese comments of LVI-SAM's code at LVI-SAM-CC_Comments.
- Origin official LVI-SAM.