# LI-Calib
## Overview
**LI-Calib** is a toolkit for calibrating the 6DoF rigid transformation and the time offset between a 3D LiDAR and an IMU. It's based on continuous-time batch optimization. IMU-based cost and LiDAR point-to-surfel distance are minimized jointly, which renders the calibration problem well-constrained in general scenarios.
## **Prerequisites**
- [ROS](http://wiki.ros.org/ROS/Installation) (tested with Kinetic and Melodic)
```shell
sudo apt-get install ros-melodic-pcl-ros ros-melodic-velodyne-msgs
```
- [Ceres](http://ceres-solver.org/installation.html) (tested with version 1.14.0)
- [Kontiki](https://github.com/APRIL-ZJU/Kontiki) (Continuous-Time Toolkit)
- Pangolin (for visualization and user interface)
- [ndt_omp](https://github.com/APRIL-ZJU/ndt_omp)
Note that **Kontiki** and **Pangolin** are included in the *thirdparty* folder.
## Install
Clone the source code for the project and build it.
```shell
# init ROS workspace
mkdir -p ~/catkin_li_calib/src
cd ~/catkin_li_calib/src
catkin_init_workspace
# Clone the source code for the project and build it.
git clone https://github.com/APRIL-ZJU/lidar_IMU_calib
# ndt_omp
wstool init
wstool merge lidar_IMU_calib/depend_pack.rosinstall
wstool update
# Pangolin
cd lidar_imu_calib_beta
./build_submodules.sh
## build
cd ../..
catkin_make
source ./devel/setup.bash
```
## Examples
Currently the LI-Calib toolkit only support `VLP-16` but it is easy to expanded for other LiDARs.
Run the calibration:
```shell
./src/lidar_IMU_calib/calib.sh
```
The options in `calib.sh` the have the following meaning:
- `bag_path` path to the dataset.
- `imu_topic` IMU topic.
- `bag_start` the relative start time of the rosbag [s].
- `bag_durr` the duration for data association [s].
- `scan4map` the duration for NDT mapping [s].
- `timeOffsetPadding` maximum range in which the timeoffset may change during estimation [s].
- `ndtResolution` resolution for NDT [m].
<img src="./pic/ui.png" alt="UI" style="zoom: 50%;" />
Following the step:
1. `Initialization`
2. `DataAssociation`
(The users are encouraged to toggle the `show_lidar_frame` for checking the odometry result. )
3. `BatchOptimization`
4. `Refinement`
6. `Refinement`
7. ...
8. (you cloud try to optimize the time offset by choose `optimize_time_offset` then run `Refinement`)
9. `SaveMap`
All the cache results are saved in the location of the dataset.
**Note that the toolkit is implemented with only one thread, it would response slowly while processing data. Please be patient**
## Dataset
<img src="./pic/3imu.png" alt="3imu" style="zoom: 67%;" />
Dataset for evaluating LI_Calib are available at [here](https://drive.google.com/drive/folders/1kYLVLMlwchBsjAoNqnrwq2N2Ow5na4VD?usp=sharing).
We utilize an MCU (stm32f1) to simulate the synchronization Pulse Per Second (PPS) signal. The LiDAR's timestamps are synchronizing to UTC, and each IMU captures the rising edge of the PPS signal and outputs the latest data with a sync signal. Considering the jitter of the internal clock of MCU, the external synchronization method has some error (within a few microseconds).
Each rosbag contains 7 topics:
```
/imu1/data : sensor_msgs/Imu
/imu1/data_sync : sensor_msgs/Imu
/imu2/data : sensor_msgs/Imu
/imu2/data_sync : sensor_msgs/Imu
/imu3/data : sensor_msgs/Imu
/imu3/data_sync : sensor_msgs/Imu
/velodyne_packets : velodyne_msgs/VelodyneScan
```
`/imu*/data` are raw data and the timestamps are coincide with the received time.
`/imu*/data_sync` are the sync data, so do `/velodyne_packets` .
## Credits
This code was developed by the [APRIL Lab](https://github.com/APRIL-ZJU) in Zhejiang University.
For researchers that have leveraged or compared to this work, please cite the following:
Jiajun Lv, Jinhong Xu, Kewei Hu, Yong Liu, Xingxing Zuo. Targetless Calibration of LiDAR-IMU System Based on Continuous-time Batch Estimation. IROS 2020. [[arxiv](https://arxiv.org/pdf/2007.14759.pdf)]
## License
The code is provided under the [GNU General Public License v3 (GPL-3)](https://www.gnu.org/licenses/gpl-3.0.txt).
赵闪闪168
- 粉丝: 1727
- 资源: 6942
最新资源
- MATLAB下的风力发电系统低电压穿越策略:串电阻技术及应用探究,MATLAB 风力发电系统低电压穿越-串电阻策略 ,核心关键词:MATLAB; 风力发电系统; 低电压穿越; 串电阻策略;,MATL
- 同步磁阻电机方波注入策略与切换方案模型设计研究,同步磁阻电机方波注入方案以及切方案模型 ,核心关键词:同步磁阻电机;方波注入方案;切换方案;模型;电控策略;电力传动 ,"同步磁阻电机方波注入及动态切换
- 西门子PLC博途三种自动流程程序写法详解:SCL Case语录与梯形图编程实践(附视频解说),西门子PLC博途3种自动流程程序写法 本案例介绍3种不同的方法去写自动流程程序 第一种是用scl cas
- 三菱FX3U PLC全功能模拟软件:虚拟串口通信与服务器仿真,高效模拟运行,节省调试时间,三菱FX3UFX2NFX1N PLC 模拟器模拟通信功能,模拟PLC实体,FX3U仿真器,仿真PLC服务器
- 基于S7-200PLC的空调与空压机变频节能控制:图解梯形程序、接线与组态实现,S7-200 MCGS 基于S7-200PLC的空调变频节能控制 空压机变频节能控制,中央空调变频节能 带解释的梯形图程
- 含热电联供的智能楼宇群协同能量管理策略:主从博弈与需求响应的融合,Matlab软件实现 ,关键词:主从博弈 需求响应 能量管理 主题:含热电联供的智能楼宇群协同能量管理 考虑了综合需求响应,主
- 基于多时间尺度滚动优化的多能源微网双层调度模型:MATLAB仿真实现与注释详实的精品代码,MATLAB代码:基于多时间尺度滚动优化的多能源微网双层调度模型 关键词:多能源微网 多时间尺度 滚动优化 微
- 基于S7-300 PLC与WinCC的自动售货控制系统设计:梯形图程序、接线图与组态画面详解,基于S7-300 PLC和Wincc自动控制系统设计3物三物 带解释的梯形图程序,接线图原理图图纸,io分
- 2.0-基于STM32的智能大棚.zip
- 基于PLC的音乐喷泉控制系统设计与实现:组态设计、梯形图程序、接线图及IO分配全解析,基于PLC音乐喷泉控制系统设计音乐喷泉组态设计音乐喷泉 带解释的梯形图程序,接线图原理图图纸,io分配,组态画面
- FMC AD9129 DAC模块:与Xilinx开发板配套,双通道射频DA芯片,高性能与便捷开发体验,FMC AD9129 DAC模块,可配套Xilinx开发板,模块采用双通道射频DA芯片AD9129
- 基于TTC和危险系数的风险评估模型:探究AEB原理与Simulink搭建实践,联合仿真实现深入了解,AEB基于危险系数,复现lun wen(相对基础) 构建了基于TTC和危险系数的风险评估模型,适合
- 基于S7-200 PLC的自动淘米洗菜与洗碗机自动控制方案:包含梯形图程序、接线图及组态画面,S7-200 MCGS 基于S7-200西门子PLC自动淘米洗菜,洗菜机,洗碗机自动控制 带解释的梯形图程
- 基于C#串口数据采集的上位机Demo:电动汽车实验平台数据展示与存储,图表化显示清晰,代码逻辑明了,适合学习者参考 ,c#通过串口采集数据,上位机采集数据Demo,图表显示,采集到的数据显示并且储存
- S7-200 PLC与MCGS组态控制的机械手控制系统:梯形图程序、接线图、IO分配与组态画面详解,S7-200 PLC和MCGS组态传送机械手的控制系统的 带解释的梯形图程序,接线图原理图图纸,io
- 基于电流检测的扰动观察法在MATLAB Simulink中实现光伏并网逆变器的MPPT控制功能函数解析,光伏并网逆变器的MPPT控制 MATLAB Simulink(基于电流检测的扰动观察法) fun
资源上传下载、课程学习等过程中有任何疑问或建议,欢迎提出宝贵意见哦~我们会及时处理!
点击此处反馈