From b98bfb3fdeaf3b8530fb8f24867d375e008b83a8 Mon Sep 17 00:00:00 2001 From: weiBUAA Date: Mon, 5 Jul 2021 23:43:58 +0800 Subject: [PATCH] add velodyne instructions --- README.md | 73 ++++++++++++++----- config/{velody16.yaml => velodyne.yaml} | 2 +- launch/gdb_debug_example.launch | 8 +- launch/mapping_avia.launch | 2 +- launch/mapping_horizon.launch | 2 +- ...elody16.launch => mapping_velodyne.launch} | 4 +- 6 files changed, 62 insertions(+), 29 deletions(-) rename config/{velody16.yaml => velodyne.yaml} (79%) rename launch/{mapping_velody16.launch => mapping_velodyne.launch} (90%) diff --git a/README.md b/README.md index fa004e8..5bd5ccd 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,19 @@ **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 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; 2. Automaticaly initialized at most steady environments; 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)
@@ -23,21 +30,18 @@ **New features:** 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. -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. 5. Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry 4B with 8G RAM. + **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) -To know more about the details, please refer to our related paper:) - **Related papers**: -our related papers are now available on arxiv: - -[FAST-LIO2: Fast Direct LiDAR-inertial Odometry (Currently Uavailable)]() +[FAST-LIO2: Fast Direct LiDAR-inertial Odometry]() (Currently Unavailable) [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** **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) ### 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** 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 Clone the repository and catkin_make: ``` - cd ~/catkin_ws/src - git clone https://github.com/XW-HKU/fast_lio.git + cd ~/$A_ROS_DIR$/src + git clone https://github.com/hku-mars/FAST_LIO.git + cd FAST_LIO git submodule update --init - cd .. + cd ../.. catkin_make 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 ```export PCL_ROOT={CUSTOM_PCL_PATH}``` ## 3. Directly run ### 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 ``` - .... - cd ~/catkin_ws + cd ~/$FAST_LIO_ROS_DIR$ + source devel/setup.bash roslaunch fast_lio mapping_avia.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. +### 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.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 rosbag play YOUR_DOWNLOADED.bag + ``` + ### 4.2 Outdoor rosbag (Livox Avia LiDAR)
@@ -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 ``` -roslaunch fast_lio mapping_avia_outdoor.launch +roslaunch fast_lio mapping_avia.launch rosbag play YOUR_DOWNLOADED.bag ``` ## 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. +The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future. +
## 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). diff --git a/config/velody16.yaml b/config/velodyne.yaml similarity index 79% rename from config/velody16.yaml rename to config/velodyne.yaml index 5cee477..974fb4e 100644 --- a/config/velody16.yaml +++ b/config/velodyne.yaml @@ -14,7 +14,7 @@ mapping: b_gyr_cov: 0.0001 fov_degree: 180 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, 0, 1, 0, 0, 0, 1] \ No newline at end of file diff --git a/launch/gdb_debug_example.launch b/launch/gdb_debug_example.launch index 5070aa1..d1f86ad 100644 --- a/launch/gdb_debug_example.launch +++ b/launch/gdb_debug_example.launch @@ -2,12 +2,6 @@ - - - - - - @@ -17,7 +11,7 @@ - + diff --git a/launch/mapping_avia.launch b/launch/mapping_avia.launch index 2f56ef7..76667ee 100644 --- a/launch/mapping_avia.launch +++ b/launch/mapping_avia.launch @@ -12,7 +12,7 @@ - + diff --git a/launch/mapping_horizon.launch b/launch/mapping_horizon.launch index 0d0cd31..e6b2aa9 100644 --- a/launch/mapping_horizon.launch +++ b/launch/mapping_horizon.launch @@ -12,7 +12,7 @@ - + diff --git a/launch/mapping_velody16.launch b/launch/mapping_velodyne.launch similarity index 90% rename from launch/mapping_velody16.launch rename to launch/mapping_velodyne.launch index 990a425..f218345 100644 --- a/launch/mapping_velody16.launch +++ b/launch/mapping_velodyne.launch @@ -3,7 +3,7 @@ - + @@ -12,7 +12,7 @@ - +