add velodyne instructions

main
weiBUAA 2021-07-05 23:43:58 +08:00
parent 1087a72497
commit b98bfb3fde
6 changed files with 62 additions and 29 deletions

View File

@ -1,12 +1,19 @@
**Noted: Ubuntu 16.04 and lower is not supported** **Noted: Ubuntu 16.04 and lower is not supported**
## Related Works
1. [ikd-Tree](https://github.com/hku-mars/ikd-Tree): A state-of-art dynamic KD-Tree for 3D kNN search.
2. [IKFOM](https://github.com/hku-mars/IKFoM): A Toolbox for fast and high-precision on-manifold Kalman filter.
3. [UAV Avoiding Dynamic Obstacles](https://github.com/hku-mars/dyn_small_obs_avoidance): One of the implementation of FAST-LIO in robot's planning.
4. [R2LIVE](https://github.com/hku-mars/dyn_small_obs_avoidance): A high-precision LiDAR-inertial-Vision fusion work using FAST-LIO as LiDAR-inertial front-end.
## FAST-LIO ## FAST-LIO
**FAST-LIO** (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues: **FAST-LIO** (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues:
1. Fast iterated Kalman filter for odometry optimization; 1. Fast iterated Kalman filter for odometry optimization;
2. Automaticaly initialized at most steady environments; 2. Automaticaly initialized at most steady environments;
3. Parallel KD-Tree Search to decrease the computation; 3. Parallel KD-Tree Search to decrease the computation;
## FAST-LIO 2.0 (2021-07-04 Update) ## FAST-LIO 2.0 (2021-07-05 Update)
<!-- ![image](doc/real_experiment2.gif) --> <!-- ![image](doc/real_experiment2.gif) -->
<!-- [![Watch the video](doc/real_exp_2.png)](https://youtu.be/2OvjGnxszf8) --> <!-- [![Watch the video](doc/real_exp_2.png)](https://youtu.be/2OvjGnxszf8) -->
<div align="left"> <div align="left">
@ -23,21 +30,18 @@
**New features:** **New features:**
1. Incremental mapping using ikd-Tree, achieve faster speed and over 100Hz LiDAR rate. 1. Incremental mapping using ikd-Tree, achieve faster speed and over 100Hz LiDAR rate.
2. Direct odometry on Raw LiDAR points (feature extraction can be closed), achieving better accuracy. 2. Direct odometry on Raw LiDAR points (feature extraction can be closed), achieving better accuracy.
3. Since no need for feature extraction, FAST-LIO2 can support different LiDAR Types including spinning (Velodyne, Ouster) and solid-state (Avia, horizon) LiDARs. And most of LiDARs can be easily supported. 3. Since no need for feature extraction, FAST-LIO2 can support different LiDAR Types including spinning (Velodyne, Ouster) and solid-state (Avia, horizon) LiDARs, and can be easily extended to support more LiDAR.
4. Support external IMU. 4. Support external IMU.
5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry 4B with 8G RAM. 5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry 4B with 8G RAM.
**Contributors** **Contributors**
[Wei Xu 徐威](https://github.com/XW-HKU)[Yixi Cai 蔡逸熙](https://github.com/Ecstasy-EC)[Dongjiao He 贺东娇](https://github.com/Joanna-HE)[Fangcheng Zhu 朱方程](https://github.com/zfc-zfc)[Jiarong Lin 林家荣](https://github.com/ziv-lin)[Zheng Liu 刘政](https://github.com/Zale-Liu) [Wei Xu 徐威](https://github.com/XW-HKU)[Yixi Cai 蔡逸熙](https://github.com/Ecstasy-EC)[Dongjiao He 贺东娇](https://github.com/Joanna-HE)[Fangcheng Zhu 朱方程](https://github.com/zfc-zfc)[Jiarong Lin 林家荣](https://github.com/ziv-lin)[Zheng Liu 刘政](https://github.com/Zale-Liu)
To know more about the details, please refer to our related paper:)
**Related papers**: **Related papers**:
our related papers are now available on arxiv: [FAST-LIO2: Fast Direct LiDAR-inertial Odometry]() (Currently Unavailable)
[FAST-LIO2: Fast Direct LiDAR-inertial Odometry (Currently Uavailable)]()
[FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter](https://arxiv.org/abs/2010.08196) [FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter](https://arxiv.org/abs/2010.08196)
@ -51,6 +55,8 @@ our related papers are now available on arxiv:
### 1.1 **Ubuntu** and **ROS** ### 1.1 **Ubuntu** and **ROS**
**Ubuntu >= 18.04 (Ubuntu 16.04 is not supported)** **Ubuntu >= 18.04 (Ubuntu 16.04 is not supported)**
For **Ubuntu 18.04 or higher**, the **default** PCL and Eigen is enough for FAST-LIO to work normally.
ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation) ROS >= Melodic. [ROS Installation](http://wiki.ros.org/ROS/Installation)
### 1.2. **PCL && Eigen && openCV** ### 1.2. **PCL && Eigen && openCV**
@ -61,33 +67,61 @@ Eigen >= 3.3.4, Follow [Eigen Installation](http://eigen.tuxfamily.org/index.ph
### 1.3. **livox_ros_driver** ### 1.3. **livox_ros_driver**
Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver). Follow [livox_ros_driver Installation](https://github.com/Livox-SDK/livox_ros_driver).
*Remarks:*
- Since the FAST-LIO must support Livox serials LiDAR firstly, so the **livox_ros_driver** must be installed and **sourced** before run any FAST-LIO luanch file.
- How to source? The easiest way is add the line ``` source $Licox_ros_driver_dir$/devel/setup.bash ``` to the end of file ``` ~/.bashrc ```, where ``` $Licox_ros_driver_dir$ ``` is the directory of the livox ros driver workspace (should be the ``` ws_livox ``` directory if you completely followed the livox official document).
## 2. Build ## 2. Build
Clone the repository and catkin_make: Clone the repository and catkin_make:
``` ```
cd ~/catkin_ws/src cd ~/$A_ROS_DIR$/src
git clone https://github.com/XW-HKU/fast_lio.git git clone https://github.com/hku-mars/FAST_LIO.git
cd FAST_LIO
git submodule update --init git submodule update --init
cd .. cd ../..
catkin_make catkin_make
source devel/setup.bash source devel/setup.bash
``` ```
*Remarks:* - Remember to source the livox_ros_driver before build (follow 1.3 **livox_ros_driver**)
- If you want to use a custom build of PCL, add the following line to ~/.bashrc - If you want to use a custom build of PCL, add the following line to ~/.bashrc
```export PCL_ROOT={CUSTOM_PCL_PATH}``` ```export PCL_ROOT={CUSTOM_PCL_PATH}```
## 3. Directly run ## 3. Directly run
### 3.1 For Avia ### 3.1 For Avia
Connect to your PC to Livox Avia LiDAR by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then Connect to your PC to Livox Avia LiDAR by following [Livox-ros-driver installation](https://github.com/Livox-SDK/livox_ros_driver), then
``` ```
.... cd ~/$FAST_LIO_ROS_DIR$
cd ~/catkin_ws source devel/setup.bash
roslaunch fast_lio mapping_avia.launch roslaunch fast_lio mapping_avia.launch
roslaunch livox_ros_driver livox_lidar_msg.launch roslaunch livox_ros_driver livox_lidar_msg.launch
``` ```
*Remarks:*
- If you want to change the frame rate, please modify the **publish_freq** parameter in the [livox_lidar_msg.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar_msg.launch) of [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) before make the livox_ros_driver pakage. - If you want to change the frame rate, please modify the **publish_freq** parameter in the [livox_lidar_msg.launch](https://github.com/Livox-SDK/livox_ros_driver/blob/master/livox_ros_driver/launch/livox_lidar_msg.launch) of [Livox-ros-driver](https://github.com/Livox-SDK/livox_ros_driver) before make the livox_ros_driver pakage.
### 3.2 For Velodyne or Ouster (using Velodyne as an example)
Step A: Setup before run
Edit ``` FAST-LIO/config/velodyne.yaml ``` to set the below parameters:
1. lidar point cloud topic name: ``` lid_topic ```
2. IMU topic name: ``` imu_topic ```
3. Line number (we tested 16 and 32 line, but not tested 64 or above): ``` scan_line ```
4. Translational extrinsic: ``` extrinsic_T ```
5. Rotational extrinsic: ``` extrinsic_R ``` (only support rotation matrix)
- The extrinsic parameters in FAST-LIO is defined as the LiDAR's pose (position and rotation matrix) in IMU body frame (i.e. the IMU is the base frame).
Step B: Run below
```
cd ~/$FAST_LIO_ROS_DIR$
source devel/setup.bash
roslaunch fast_lio mapping_velodyne.launch
```
Step C: Run LiDAR's ros driver or play rosbag.
*Remarks:*
- We will produce some velodyne datasets which is already transfered to Rosbags, please wait for a while.
## 4. Rosbag Example ## 4. Rosbag Example
### 4.1 Indoor rosbag (Livox Avia LiDAR) ### 4.1 Indoor rosbag (Livox Avia LiDAR)
@ -97,7 +131,9 @@ Download [avia_indoor_quick_shake_example1](https://drive.google.com/file/d/1SWm
``` ```
roslaunch fast_lio mapping_avia.launch roslaunch fast_lio mapping_avia.launch
rosbag play YOUR_DOWNLOADED.bag rosbag play YOUR_DOWNLOADED.bag
``` ```
### 4.2 Outdoor rosbag (Livox Avia LiDAR) ### 4.2 Outdoor rosbag (Livox Avia LiDAR)
<div align="center"><img src="doc/results/HKU_MB_002.png" width=100% /></div> <div align="center"><img src="doc/results/HKU_MB_002.png" width=100% /></div>
@ -106,17 +142,20 @@ rosbag play YOUR_DOWNLOADED.bag
Download [avia_hku_main building_mapping](https://drive.google.com/file/d/1GSb9eLQuwqmgI3VWSB5ApEUhOCFG_Sv5/view?usp=sharing) and then Download [avia_hku_main building_mapping](https://drive.google.com/file/d/1GSb9eLQuwqmgI3VWSB5ApEUhOCFG_Sv5/view?usp=sharing) and then
``` ```
roslaunch fast_lio mapping_avia_outdoor.launch roslaunch fast_lio mapping_avia.launch
rosbag play YOUR_DOWNLOADED.bag rosbag play YOUR_DOWNLOADED.bag
``` ```
## 5.Implementation on UAV ## 5.Implementation on UAV
In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below. In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below.
The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future.
<div align="center"> <div align="center">
<img src="doc/uav01.jpg" width=40.5% > <img src="doc/uav01.jpg" width=40.5% >
<img src="doc/uav_system.png" width=57% > <img src="doc/uav_system.png" width=57% >
</div> </div>
## 6.Acknowledgments ## 6.Acknowledgments
Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Livox_Mapping](https://github.com/Livox-SDK/livox_mapping) and [Loam_Livox](https://github.com/hku-mars/loam_livox).
Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), [Livox_Mapping](https://github.com/Livox-SDK/livox_mapping), [LINS](https://github.com/ChaoqinRobotics/LINS---LiDAR-inertial-SLAM) and [Loam_Livox](https://github.com/hku-mars/loam_livox).

View File

@ -14,7 +14,7 @@ mapping:
b_gyr_cov: 0.0001 b_gyr_cov: 0.0001
fov_degree: 180 fov_degree: 180
det_range: 100.0 det_range: 100.0
extrinsic_T: [ 0, 0, 0.28] #ULHK #[ -0.5, 1.4, 1.5 ] #utbm extrinsic_T: [ 0, 0, 0.28]
extrinsic_R: [ 1, 0, 0, extrinsic_R: [ 1, 0, 0,
0, 1, 0, 0, 1, 0,
0, 0, 1] 0, 0, 1]

View File

@ -2,12 +2,6 @@
<arg name="rviz" default="true" /> <arg name="rviz" default="true" />
<node pkg="fast_lio" type="loam_feat_extract" name="feature_extract" output="log" />
<param name="lidar_type" type="int" value="1"/>
<param name="feature_extract_enable" type="bool" value="0"/>
<param name="blind" type="double" value="1"/>
<param name="point_filter_num" type="int" value="3"/>
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" required="true" launch-prefix="gdb -ex run --args"> <node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" required="true" launch-prefix="gdb -ex run --args">
<param name="imu_topic" type="string" value="/livox/imu" /> <param name="imu_topic" type="string" value="/livox/imu" />
<param name="map_file_path" type="string" value=" " /> <param name="map_file_path" type="string" value=" " />
@ -17,7 +11,7 @@
<param name="filter_size_corner" type="double" value="0.2" /> <param name="filter_size_corner" type="double" value="0.2" />
<param name="filter_size_surf" type="double" value="0.2" /> <param name="filter_size_surf" type="double" value="0.2" />
<param name="filter_size_map" type="double" value="0.5" /> <param name="filter_size_map" type="double" value="0.5" />
<param name="runtime_pos_log" type="bool" value="1" /> <param name="runtime_pos_log_enable" type="bool" value="1" />
<param name="cube_side_length" type="double" value="2000" /> <param name="cube_side_length" type="double" value="2000" />
</node> </node>

View File

@ -12,7 +12,7 @@
<param name="filter_size_surf" type="double" value="0.5" /> <param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" /> <param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" /> <param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log" type="bool" value="0" /> <param name="runtime_pos_log_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" /> <node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)"> <group if="$(arg rviz)">

View File

@ -12,7 +12,7 @@
<param name="filter_size_surf" type="double" value="0.5" /> <param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" /> <param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" /> <param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log" type="bool" value="0" /> <param name="runtime_pos_log_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" /> <node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)"> <group if="$(arg rviz)">

View File

@ -3,7 +3,7 @@
<arg name="rviz" default="true" /> <arg name="rviz" default="true" />
<rosparam command="load" file="$(find fast_lio)/config/velody16.yaml" /> <rosparam command="load" file="$(find fast_lio)/config/velodyne.yaml" />
<param name="feature_extract_enable" type="bool" value="0"/> <param name="feature_extract_enable" type="bool" value="0"/>
<param name="point_filter_num" type="int" value="4"/> <param name="point_filter_num" type="int" value="4"/>
@ -12,7 +12,7 @@
<param name="filter_size_surf" type="double" value="0.5" /> <param name="filter_size_surf" type="double" value="0.5" />
<param name="filter_size_map" type="double" value="0.5" /> <param name="filter_size_map" type="double" value="0.5" />
<param name="cube_side_length" type="double" value="1000" /> <param name="cube_side_length" type="double" value="1000" />
<param name="runtime_pos_log" type="bool" value="0" /> <param name="runtime_pos_log_enable" type="bool" value="0" />
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" /> <node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen" />
<group if="$(arg rviz)"> <group if="$(arg rviz)">