Lenotary a2e9cb769f first commit | 2 years ago | |
---|---|---|
.github | 2 years ago | |
config | 2 years ago | |
include | 2 years ago | |
launch | 2 years ago | |
msg | 2 years ago | |
src | 2 years ago | |
CMakeLists.txt | 2 years ago | |
LICENSE | 2 years ago | |
README.md | 2 years ago | |
package.xml | 2 years ago |
A real-time lidar-inertial odometry package. We strongly recommend the users read this document thoroughly and test the package with the provided dataset first. A video of the demonstration of the method can be found on YouTube.
Prepare lidar data (must read)
Prepare IMU data (must read)
We design a system that maintains two graphs and runs up to 10x faster than real-time.
ROS (tested with Kinetic and Melodic)
sudo apt-get install -y ros-kinetic-navigation
sudo apt-get install -y ros-kinetic-robot-localization
sudo apt-get install -y ros-kinetic-robot-state-publisher
gtsam (Georgia Tech Smoothing and Mapping library)
wget -O ~/Downloads/gtsam.zip https://github.com/borglab/gtsam/archive/4.0.2.zip
cd ~/Downloads/ && unzip gtsam.zip -d ~/Downloads/
cd ~/Downloads/gtsam-4.0.2/
mkdir build && cd build
cmake -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF ..
sudo make install -j8
Use the following commands to download and compile the package.
cd ~/catkin_ws/src
git clone https://github.com/TixiaoShan/LIO-SAM.git
cd ..
catkin_make
The user needs to prepare the point cloud data in the correct format for cloud deskewing, which is mainly done in "imageProjection.cpp". The two requirements are:
IMU requirement. Like the original LOAM implementation, LIO-SAM only works with a 9-axis IMU, which gives roll, pitch, and yaw estimation. The roll and pitch estimation is mainly used to initialize the system at the correct attitude. The yaw estimation initializes the system at the right heading when using GPS data. Theoretically, an initialization procedure like VINS-Mono will enable LIO-SAM to work with a 6-axis IMU. The performance of the system largely depends on the quality of the IMU measurements. The higher the IMU data rate, the better the system accuracy. We use Microstrain 3DM-GX5-25, which outputs data at 500Hz. We recommend using an IMU that gives at least a 200Hz output rate. Note that the internal IMU of Ouster lidar is an 6-axis IMU.
IMU alignment. LIO-SAM transforms IMU raw data from the IMU frame to the Lidar frame, which follows the ROS REP-105 convention (x - forward, y - left, z - upward). To make the system function properly, the correct extrinsic transformation needs to be provided in "params.yaml" file. The reason why there are two extrinsics is that my IMU (Microstrain 3DM-GX5-25) acceleration and attitude have different cooridinates. Depend on your IMU manufacturer, the two extrinsics for your IMU may or may not be the same. Using our setup as an example:
IMU debug. It's strongly recommended that the user uncomment the debug lines in "imuHandler()" of "imageProjection.cpp" and test the output of the transformed IMU data. The user can rotate the sensor suite to check whether the readings correspond to the sensor's movement. A YouTube video that shows the corrected IMU data can be found here (link to YouTube).
Download some sample datasets to test the functionality of the package. The datasets below is configured to run using the default settings:
The datasets below need the parameters to be configured. In these datasets, the point cloud topic is "points_raw." The IMU topic is "imu_correct," which gives the IMU data in ROS REP105 standard. Because no IMU transformation is needed for this dataset, the following configurations need to be changed to run this dataset successfully:
Ouster (OS1-128) dataset. No extrinsics need to be changed for this dataset if you are using the default settings. Please follow the Ouster notes below to configure the package to run with Ouster data. A video of the dataset can be found on YouTube:
KITTI dataset. The extrinsics can be found in the Notes KITTI section below. To generate more bags using other KITTI raw data, you can use the python script provided in "config/doc/kitti2bag".
Run the launch file:
roslaunch lio_sam run.launch
Play existing bag files:
rosbag play your-bag.bag -r 3
086759e
-01, 3.195559e
-01, -7.997231e
-01]999976e
-01, 7.553071e
-04, -2.035826e
-03, -7.854027e
-04, 9.998898e
-01, -1.482298e
-02, 2.024406e
-03, 1.482454e
-02, 9.998881e
-01]999976e
-01, 7.553071e
-04, -2.035826e
-03, -7.854027e
-04, 9.998898e
-01, -1.482298e
-02, 2.024406e
-03, 1.482454e
-02, 9.998881e
-01]
Zigzag or jerking behavior: if your lidar and IMU data formats are consistent with the requirement of LIO-SAM, this problem is likely caused by un-synced timestamp of lidar and IMU data.
Jumpping up and down: if you start testing your bag file and the base_link starts to jump up and down immediately, it is likely your IMU extrinsics are wrong. For example, the gravity acceleration has negative value.
mapOptimization crash: it is usually caused by GTSAM. Please install the GTSAM specified in the README.md. More similar issues can be found here.
Thank you for citing LIO-SAM (IROS-2020) if you use any of this code.
@inproceedings{liosam2020shan,
title={LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping},
author={Shan, Tixiao and Englot, Brendan and Meyers, Drew and Wang, Wei and Ratti, Carlo and Rus Daniela},
booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
year={2020},
organization={IEEE}
}
Part of the code is adapted from LeGO-LOAM.
@inproceedings{legoloam2018shan,
title={LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain},
author={Shan, Tixiao and Englot, Brendan},
booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
pages={4758-4765},
year={2018},
organization={IEEE}
}