LIV-Eye: A Low-Cost LiDAR-Inertial-Visual Fusion 3D Sensor for Robotics and Embodied AI [中文]
- Highlights
- Repository Structure
- Bill of Materials (BOM)
- Assembly
- Wiring
- Driver Installation and Run
- LiDAR-Camera Joint Calibration
- Running FAST-LIVO2
- Platform Adaptability
- Acknowledgements
- License
One sentence summary: A ~¥5000 (≈ $700) fully open-source hardware/software LiDAR-Inertial-Visual fusion perception kit. ⚙️ Easy assembly, no soldering, one-click reproducibility. 🐳 Supports ROS1/ROS2 and Docker, 🧭 full calibration workflow (intrinsic/extrinsic/time sync), 🧰 compatible with FAST-LIVO2 algorithms, and delivers colored point cloud and odometry results in just 5 minutes.
├── FAST-LIVO2-Mid360-Config - The configuration and launch files of FAST-LIVO2 for the Mid-360 LiDAR
├── liv_eye_cad - Solidworks files for LIV-Eye
├── livox_ros_driver2 - Livox LiDAR ROS driver
├── mvs_ros_driver - Hikvision Camera ROS driver
└── README.md - Project homepage
└── ...
Target total cost: ≈ ¥5,000 (≈ $700, subject to actual purchase)
| Category | Model/Name | Reference Price | Image |
|---|---|---|---|
| LiDAR | Livox Mid-360 | ¥3999 (≈ $560) | ![]() |
| Camera | Hikvision MV-CU013-A0UC | ¥700 (≈ $100) | ![]() |
| Lens | Hikvision MVL-HF0628M-6MPE | ¥150 (≈ $20) | ![]() |
| Wire | LiDAR-Camera Hardware Synchronizer | ¥500 (≈ $70) | ![]() |
| Battery | 12V DC Battery | ¥99 (≈ $15) | ![]() |
Solidworks CAD files are provided in liv_eye_cad.
You can download and use them for 3D printing and assembly:
The diagram below shows the complete wiring of LIV-Eye, in just six steps:
Note
If you do not need to use the LiDAR-Camera hardware synchronizer, please refer to the connection method and STM32 hardware synchronization solution in LIV_handhold.
-
Download and install MVS and Livox-SDK2. Set the camera to trigger mode in MVS.
-
Install the camera ROS driver mvs_ros_driver and launch in trigger mode:
roslaunch mvs_ros_driver mvs_camera_trigger.launch - Install and launch the LiDAR ROS driver livox_ros_driver2:
roslaunch livox_ros_driver2 msg_MID360.launch- Record sensor data:
rosbag record /livox/lidar /livox/imu /left_camera/imageNote
The mvs_ros_driver and livox_ros_driver2 are the same as those in LIV_handhold, and include modifications to support millisecond-level hardware synchronization.
- Calibrate camera intrinsics. e.g. matlab.
- Use FAST-Calib for LiDAR–camera extrinsic calibration.
Install FAST-LIVO2. The configuration and launch files for the Mid-360 are provided in FAST-LIVO2-Mid360-Config. Update the intrinsic and extrinsic parameters to match your device, then run:
roslaunch fast_livo mapping_mid360.launchThis demo corresponds to the example LIV-Eye rosbag, which can be downloaded here.
LIV-Eye is compact yet versatile! With its small form factor, standardized wiring, and open-source software, it can be seamlessly integrated into a wide range of robotic platforms to enable perception, navigation, and embodied AI research.
This project is based on the following open-source projects:
- Driver and time synchronization: LIV_handhold
- Calibration method: FAST-Calib
- Algorithm: FAST-LIVO2
- CAD Design: Link by pcl5
The source code is released under the GPLv2 license.
If you use this codebase in academic research, please cite any of the following papers:
[1] Zheng, Chunran, et al. "FAST-LIVO2: Fast, Direct LiDAR-Inertial-Visual Odometry."
[2] Zheng, Chunran, et al. "FAST-LIVO: Fast and Tightly-coupled Sparse-Direct LiDAR-Inertial-Visual Odometry."
[3] Zheng, Chunran, et al. "FAST-Calib: LiDAR-Camera Extrinsic Calibration in One Second."
[4] Ziming, Wang, et al. "USTC FLICAR: A sensors fusion dataset of LiDAR-inertial-camera for heavy-duty autonomous aerial work robots."













