- We release a modified version that changed LIO-SAM to LIORF in here!!
$ git clone --branch liorf https://github.com/sparolab/Distributed-SOLiD-SLAM.git
- Distributed SOLiD SLAM is a Distributed SOLiD-based LiDAR SLAM Framework, which is a modified version of LIO-SAM and DiSCo-SLAM. (Scan Context → SOLiD)
- The information exchange between robots is made through ROS-based communication. (More detailed in here!!)
- SOLiD, which is a lightweight descriptor enables fast communication between robots.
- Ubuntu 20.04
- GTSAM (Develop version)
- libnabo 1.0.7
Linux
$ cd ~/catkin_ws/src
$ git clone https://github.com/sparolab/Distributed-SOLiD-SLAM.git
$ cd ..
$ catkin_make
$ source devel/setup.bash
$ roslaunch lio_sam run.launch
$ rosbag play (your dataset).bag
Docker
$ cd ~/catkin_ws/src
$ git clone https://github.com/sparolab/Distributed-SOLiD-SLAM.git
$ docker pull cokr6901/distributed_solid_slam
$ docker run --privileged --gpus all \
-it --name distributed_solid_slam --ipc=host --shm-size=512M \
--device=/dev/video0:/dev/video0 -v /tmp/.X11-unix:/tmp/.X11-unix:ro \
-e DISPLAY=unix$DISPLAY -v /root/.Xauthority:/root/.Xauthority \
--env="QT_X11_NO_MITSHM=1" \
-v ~/catkin_ws/src/:/home/test_ws/src -v (your dataset folder path)/:/home/test_ws/storage cokr6901/distributed_solid_slam:latest
$ cd /home/test_ws/
$ catkin_make
$ source devel/setup.bash
$ roslaunch lio_sam run.launch
$ rosbag play (your dataset).bag
Extrinsic (LiDAR -> IMU)
extrinsicTrans: [0.0, 0.0, 0.0]
extrinsicRot: [-1, 0, 0,
0, 1, 0,
0, 0, -1]
extrinsicRPY: [0, 1, 0,
-1, 0, 0,
0, 0, 1]
SOLiD
mapfusion:
solid:
knn_feature_dim: 40
max_range: 80
num_sector: 60
num_height: 64
num_nearest_matches: 50
num_match_candidates: 1
fov_up: 2.0
fov_down: -24.8
Generate a multi-robot rosbag from a single-robot rosbag using a Python script. (reference: here )
$ python3 split.bag -i (input.bag) -o (output.bag)
You can edit these lines.
topics = ['/points_raw', '/imu_raw', '/gps/fix'] # Rostopic names
split_places = [90, 180, 290] # 0(start)-90-180-290(final)
robot_names = ['/jackal0', '/jackal1', '/jackal2'] # Robot names (jackal0:0-90 / jackal1:90-180 / jackal2:180-290)
- You can see the results of the Park dataset (i.e. DiSCo SLAM dataset) here!!
- Save the transformed paths.
- Change the LiDAR-Odometry. (LIO-SAM → FAST-LIO2)
- Add the outlier rejection. (e.g. RANSAC)
- Add the traversability mapping.
@article{kim2024narrowing,
title={Narrowing your FOV with SOLiD: Spatially Organized and Lightweight Global Descriptor for FOV-constrained LiDAR Place Recognition},
author={Kim, Hogyun and Choi, Jiwon and Sim, Taehu and Kim, Giseop and Cho, Younggun},
journal={IEEE Robotics and Automation Letters},
year={2024},
publisher={IEEE}
}
- Hogyun Kim (hg.kim@inha.edu)
- Juwon Kim (lambertkim@naver.com)
- We appreciate Prof. Brendan Englot's RobustFieldAutonomyLab, particularly Yewei Huang, for publishing the DiSCo-SLAM.