DS-PTAM, a distributed architecture for the S-PTAM stereo SLAM system. DS-PTAM is developed on the ROS framework, separating the localization and mapping tasks into two independent ROS nodes. The DS-PTAM system is ideal for mobile robots with low computing power because it allows to run the localization module on-board and the mapping module —which has a higher computational cost— on a remote base station, relieving the load on the on-board processor. The proposed architecture was implemented based on the original S-PTAM monolithic code and then validated through different experiments on public datasets. The results obtained show the feasibility of the proposed distributed architecture, its correct implementation and the benefits of distributing the computational load on several computers.
[1] De Croce, Mauro; Pire, Taihú; Bergero, Federico. DS-PTAM: Distributed Stereo Parallel Tracking and Mapping SLAM System Journal of Intelligent & Robotic Systems, 2018. ISSN: 0921-0296. DOI: 10.1007/s10846-018-0913-6
[2] Taihú Pire, Thomas Fischer, Javier Civera, Pablo De Cristóforis and Julio Jacobo Berlles.
Stereo Parallel Tracking and Mapping for Robot Localization
Proc. of The International Conference on Intelligent Robots and Systems (IROS), Hamburg, Germany, 2015.
Table of Contents generated with DocToc
S-PTAM is released under GPLv3 license.
This site and the code provided here are under active development. Even though we try to only release working high quality code, this version might still contain some issues. Please use it with caution.
We have tested S-PTAM in Ubuntu 16.04 with ROS Kinetic.
To install ROS (kinetic) use the following command:
sudo apt-get install ros-kinetic-desktop
Install our ros-utils library from the source code provided in
git clone [email protected]:lrse/ros-utils.git
Install g2o using the following command:
sudo apt install ros-kinetic-libg2o
Install PCL using the following command:
sudo apt install ros-kinetic-pcl-ros
https://github.com/CIFASIS/distributed-sptam
catkin_make --pkg sptam -DSHOW_TRACKED_FRAMES=ON
SHOW_TRACKED_FRAMES=([ON|OFF], default: OFF)
Show the tracked frames by S-PTAM. Set it OFF to improve S-PTAM performance.
SHOW_PROFILING=([ON|OFF], default: ON)
Log in /tmp folder. Set it OFF to improve S-PTAM performance.
DSHOW_PRINTS=([ON|OFF], default: OFF)
Show info on screen. Set it OFF to improve S-PTAM performance.
We provide some examples of how to run with the most popular stereo datasets
-
Download the KITTI rosbag kitti_00.bag provided in KITTI rosbag files
-
Uncompress the dataset
rosbag decompress kitti_00.bag
-
Set use_sim_time ros variable true
rosparam set use_sim_time true
-
Play the dataset
rosbag play kitti_00.bag
(When S-PTAM run with the flag SHOW_TRACKED_FRAMES=ON the performance is reduced notoriusly).
-
Download the EuRoC Machine Hall 01 rosbag provided in EuRoC rosbag files
-
Uncompress the dataset
rosbag decompress MH_01_easy.bag
-
Set use_sim_time ros variable true
rosparam set use_sim_time true
-
Play the dataset
rosbag play MH_01_easy.bag
(When S-PTAM run with the flag SHOW_TRACKED_FRAMES=ON the performance is reduced notoriusly).
Examples for KITTI dataset:
roslaunch sptam dsptam_kitti.launch
roslaunch sptam dsptam_kitti-tracker.launch
In PC 1 (master):
export ROS_IP=192.168.1.1
In PC 2 (client):
export ROS_IP=192.168.1.2
export ROS_MASTER_URI=http://192.168.1.1:11311
IP master PC and port 11311.
In PC 1:
roslaunch sptam dsptam_kitti-tracker.launch
In PC 2:
roslaunch sptam dsptam_kitti-mapper.launch