This repository adapts the state-of-the-art LiDAR-Inertial-Visual odometry system, FAST-LIVO, to our lidar product Active Camera.
FAST-LIVO is a fast LiDAR-Inertial-Visual odometry system, which builds on two tightly-coupled and direct odometry subsystems: a VIO subsystem and a LIO subsystem. The LIO subsystem registers raw points (instead of feature points on e.g., edges or planes) of a new scan to an incrementally-built point cloud map. The map points are additionally attached with image patches, which are then used in the VIO subsystem to align a new image by minimizing the direct photometric errors without extracting any visual features (e.g., ORB or FAST corner features).
If you need further information about the FAST-LIVO algorithm, you can refer to their official website and contributors:
- Website: https://github.com/hku-mars/FAST-LIVO
- Contributors: Chunran Zheng 郑纯然, Qingyan Zhu 朱清岩, Wei Xu 徐威
The following examples show mapping outputs captured with the RoboSense AC sensor in both outdoor and indoor environments. Demo data can be downloaded at wiki page
Follow the specified content in the official tutorial for your operating system.
Sophus Installation for the non-templated/double-only version.
git clone https://github.com/strasdat/Sophus.git
cd Sophus
git checkout a621ff
mkdir build && cd build && cmake ..
make
sudo make installClone this repository into a create an existing ros1 workspace and execute the following command to build:
cd <your_workspace>
catkin_make # or catkin buildClone this repository into a create an existing ros2 workspace and execute the following command to build and install:
source <robosense_ac_ros2_sdk_infra_workspace>/install/setup.bash
colcon build --symlink-install Edit config/RS_META.yaml to set the below parameters:
lid_topic: The topic name of LiDAR data.imu_topic: The topic name of IMU data.img_topic: The topic name of camera data.img_enable: Enbale vio submodule.lidar_enable: Enbale lio submodule.point_filter_num: The sampling interval for a new scan. It is recommended that3~4for faster odometry, and1~2for denser map.outlier_threshold: The outlier threshold value of photometric error (square) of a single pixel. It is recommended that50~250for the darker scenes, and500~1000for the brighter scenes. The smaller the value is, the faster the vio submodule is, but the weaker the anti-degradation ability is.img_point_cov: The covariance of photometric errors per pixel.laser_point_cov: The covariance of point-to-plane redisual per point.filter_size_surf: Downsample the points in a new scan. It is recommended that0.05~0.15for indoor scenes,0.3~0.5for outdoor scenes.filter_size_map: Downsample the points in LiDAR global map. It is recommended that0.15~0.3for indoor scenes,0.4~0.5for outdoor scenes.pcd_save_en: Iftrue, save point clouds to the PCD folder. Save RGB-colored points ifimg_enableis1, intensity-colored points ifimg_enableis0.delta_time: The time offset between the camera and LiDAR, which is used to correct timestamp misalignment.
After setting the appropriate topic name and parameters, you can directly run RS-FAST-LIVO on the dataset.
Extrinsic and intrinsic parameters of the sensor are set in config/calibration.yaml
You don't need to change parameters in calibration.yaml
# In the root of your workspace
source devel/setup.bash # replace setup.bash with setup.zsh if you're using zsh
roslaunch slam mapping_meta.launchNon-zero-copy mode
source <robosense_ac_ros2_sdk_infra_workspace>/install/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE=ac_driver/conf/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=0
source install/setup.bash
ros2 run slam slam_nodeZero-copy mode (only for ROS2 Humble)
source <robosense_ac_ros2_sdk_infra_workspace>/install/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE=ac_driver/conf/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
source install/setup.bash
ros2 run slam slam_node
Thanks for FAST-LIVO, FAST-LIVO2 and VINS-Mono
The source code of this package is released under GPLv2 license.


