Skip to content

hku-mars/Swarm-LIO2

Repository files navigation

Swarm-LIO2

Swarm-LIO2: Decentralized, Effcient LiDAR-inertial Odometry for UAV Swarms

IEEE Transactions on Robotics '25
Fangcheng Zhu, Yunfan REN Longji Yin, Fanze Kong, Qingbo Liu, Ruize Xue, Wenyi Liu, Yixi Cai, Guozheng Lu, Haotian Li, and Fu Zhang


HKU MaRS Lab

Bilibili Youtube

Introduction

Swarm-LIO2 is a fully decentralized, plug-and-play, computationally efficient, and bandwidth-efficient LiDAR-inertial odometry for aerial swarm systems.

Our package address following key issues for a UAV swarm system:

  1. Robust, real-time, accurate ego-state estimation and mutual state estimation.
  2. High quality global extrinsic calibration.
  3. Superior computation and communication efficiency which supports large swarm scales.
  4. Excellent robustness in various scenarios: indoor, outdoor, dark night, degenerate corridors...
  5. Support diverse UAV swarm applications: target tracking, collaborative exploration, payload transportation...

Improvements

Swarm-LIO2 improves our previous work Swarm-LIO (see below) mainly in five crucial aspects:

  1. Fast Initialization: factor graph optimization is utilized for efficient identification and global extrinsic calibration, which largely decreases the complexity and energy consumption of the swarm initialization.
  2. Efficient Computation: novel marginalization and degeneration evaluation are presented to alleviate computation burden and to support large swarm scales.
  3. Detailed Modeling: detailed measurement modeling and temporal compensation of the mutual observation measurements are proposed, which mitigates the approximation error when fusing data.
  4. Comprehensive Experiments: more extensive experiments in both simulated and real-world environments are conducted, which demonstrate superior performances in terms of robustness, efficiency, and wide supportability to diverse aerial swarm applications.
  5. Open Source: all the system designs will be open-sourced to contribute the robotic society.

Related Paper

Related paper is available on arxiv: Swarm-LIO2.

Related Video

The accompanying video of Swarm-LIO2 is available on YouTube and Bilibili:

## Code

1. Prerequisites

1.1 Ubuntu and ROS

Ubuntu = 20.04.

ROS = Noetic. ROS Installation

1.2. PCL && Eigen

PCL >= 1.8, Follow PCL Installation.

Eigen >= 3.3.4, Follow Eigen Installation.

1.3. livox_ros_driver or livox_ros_driver2

Follow livox_ros_driver Installation or livox_ros_driver2 Installation .

Remarks:

  • Since the Swarm-LIO2 must support Livox serials LiDAR firstly, so the livox_ros_driver or livox_ros_driver2 (select correct LiDAR driver according to your LiDAR) must be installed and sourced before run any Swarm-LIO2 luanch file.

1.4 GTSAM

sudo apt-get install libboost-all-dev
sudo apt-get install cmake
sudo apt-get install libtbb-dev

Download GTSAM from Swarm-LIO2 data and dependencies, and

mkdir build
cd build
cmake ..
make check (optional, runs unit tests)
make install
sudo cp /usr/local/lib/libgtsam.so.4 /usr/lib
sudo cp /usr/local/lib/libmetis-gtsam.so /usr/lib

2. Build

Clone the repository and catkin_make:

cd ~/swarm_ws/src
git clone [email protected]:hku-mars/Swarm-LIO2.git
cd ..
catkin_make -j
source devel/setup.bash

3. Calibrate LiDAR-IMU

The LI-Init: robust real-time LiDAR-IMU initialization toolkit is recommended.

The calibrated extrinsic and temporal offset should be correctly modified in xxx.yaml file.

4. Tune parameters

Edit config/xxx.yaml and fill in the appropriate parameters.

More details on the meanings of the parameters and methods for adjustment will be provided later.

5. Directly run on the onboard UAV

Run the UDP communication module:

cd swarm_ws
source devel/setup.bash
roslaunch udp_bridge udp_online.launch

Run the state estimation module of Swarm-LIO2:

cd swarm_ws
source devel/setup.bash
roslaunch swarm_lio livox_mid360.launch

6. Play example rosbag

Download example rosbag (real-world data) -- mutual_avoidance_uav1.bag -- from Swarm-LIO2 data and dependencies, then

cd swarm_ws
source devel/setup.bash
roslaunch swarm_lio livox_mid360.launch
rosbag play mutual_avoidance_uav1.bag

Previous Work: Swarm-LIO

Swarm-LIO is a fully decentralized state estimation method for aerial swarm systems, in which each drone performs precise ego-state estimation, exchanges ego-state and mutual observation information by wireless communication, and estimates relative state with respect to (w.r.t.) the rest of UAVs, all in real-time and only based on LiDAR-inertial measurements.

Related Paper

Our related papers are now available: Swarm-LIO: Decentralized Swarm LiDAR-inertial Odometry

Bibtex format:

@inproceedings{zhu2023swarm,
  title={Swarm-lio: Decentralized swarm lidar-inertial odometry},
  author={Zhu, Fangcheng and Ren, Yunfan and Kong, Fanze and Wu, Huajie and Liang, Siqi and Chen, Nan and Xu, Wei and Zhang, Fu},
  booktitle={2023 IEEE International Conference on Robotics and Automation (ICRA)},
  pages={3254--3260},
  year={2023},
  organization={IEEE}
}

Related Video:

Our accompanying videos are now available on YouTube and Bilibili (click below images to open)

About

[T-RO 24] Swarm-LIO2: Decentralized, Efficient LiDAR-inertial Odometry for UAV Swarms

Topics

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published