Evaluation of the RGB-D SLAM system

This page describes how to reproduce the results of our evaluation. The installation and benchmarking steps of the below guide are concatenated in this script. Be warned, it will download huge amounts of data and put heavy computational and i/o load on your computer.

Note: you can download the trajectories estimated by RGB-D SLAM from here (for example, to compare the performance of your own system to RGB-D SLAM).

Installation

Preconditions

This guide was tested with these preconditions:

  • Ubuntu 10.10 or 11.04, 64bit Version (see your /etc/issue and the output of uname -m)

  • ROS diamondback or electric (required for ORB) is installed
  • Qt4 installed as default Qt version (check/change with "update-alternatives --display qmake")
  • Optional: OpenGL Hardware Support, required for visualization and SIFTGPU

If you do not already have a directory for personal ROS packages, create one like this:

mkdir -p ~/ros
echo 'export ROS_PACKAGE_PATH=~/ros:$ROS_PACKAGE_PATH' >> ~/.bashrc
source ~/.bashrc

The remainder of this description assumes you chose ~/ros/ as your personal package path. Otherwise you need to adapt the paths below, where ~/ros is contained to fit your directory strucure.

RGB-D SLAM (+ Requirements)

Download g2o to your personal package path:

svn co https://code.ros.org/svn/ros-pkg/stacks/vslam/trunk/g2o ~/ros/g2o

Download the RGB-D SLAM source code and extract the archive to your personal package path:

wget --no-check-certificate https://www.informatik.uni-freiburg.de/~endres/rgbdslam/rgbdslam.tgz
tar xzf rgbdslam.tgz -C ~/ros/

This guide was tested with the above version. If you use Ubuntu 11.10 or want to try using the latest (newer) release, you can get RGBDSLAM from the subversion repository

svn co http://alufr-ros-pkg.googlecode.com/svn/trunk/rgbdslam_freiburg/rgbdslam

Compile rgbdslam and g2o.

rosmake --rosdep-install rgbdslam

This takes quite a time (20min on an old laptop with core2 cpu T5600 at 1.83GHz). You can advance to the next section and fetch the benchmark data and tools meanwhile. Using "export ROS_PARALLEL_JOBS=-jX" with X being the number of your cpu cors at maximum, will speed the compilation up by a factor of X, but will need huge amounts of memory (~ 1GB per core).

If ros dependency resolution failed for your system for some reason, you need to install the system dependencies manually:

sudo apt-get install libglew1.5-dev libdevil-dev libsuitesparse-dev

If this fails and you can not figure out the solution, please inquire with endres(at)informatik.uni-freiburg.de

Evaluation Requirements

To evaluate RGB-D SLAM with the RGB-D Benchmark you need to download the benchmark tools.

svn co https://svncvpr.in.tum.de/cvpr-ros-pkg/trunk/rgbd_benchmark/rgbd_benchmark_tools ~/ros/rgbd_benchmark_tools

The bagfiles need to be downloaded separately. Execute the following script to do so (Warning: Downloads several gigabytes):

rosrun rgbdslam download_benchmark_files.sh

The bag files are compressed to save disk space. To achieve the regular performance you need to decompress them

for file in $(rospack find rgbdslam)/rgbd_benchmark/benchmark_data/*bag; do
  echo $file;
  rosbag decompress $file;
done
rm $(rospack find rgbdslam)/rgbd_benchmark/benchmark_data/*.orig.bag  # This removes the original (compressed) files. If you want to keep them, move them to another directory

Octomapping Requirements

The following commands will checkout the packages required for generation of colored octomaps and compile the octomapping stack.

svn co https://alufr-ros-pkg.googlecode.com/svn/branches/octomap_mapping_color ~/ros/octomap_mapping_color
svn co https://code.ros.org/svn/wg-ros-pkg/stacks/motion_planning_common/trunk ~/ros/motion_planning_common
rosmake motion_planning_common
rosmake --rosdep-install octomap_mapping_color

Running RGB-D SLAM on the Benchmark dataset

The following script will run the RGB-D SLAM system on all sequences in the dataset:

rosrun rgbdslam benchmark_evaluation.sh <feature-type> ~/ros/rgbdslam/rgbd_benchmark/benchmark_data/

This generates the trajectory estimation for each sequence for the given feature type. Valid feature types are SURF, SIFT, SIFTGPU, and (for ROS electric only) ORB.

To compare the generated trajectories with the respective ground truth trajectories run

rosrun rgbdslam summarize_evaluation.sh ~/ros/rgbdslam/rgbd_benchmark/benchmark_data/<feature-type>

This generates a comprehensive summary in the file ".../<feature-type>/evaluation_1.csv" file. Using Open/Libre Office, you can open it (make sure space is no delimiter) and paste the results into "spreadsheet_template.ods" which generates mean values and nice plots for accuracy and runtime

Customization of the Experiments

Using the tools above, you can quickly generate results for different settings of parameters. The parameters that change the behaviour of RGB-D SLAM can be changed in settings_for_evaluation.launch:

rosed rgbdslam settings_for_evaluation.launch

All available settings are shown and explained in rgbdslam_sample_config.launch in the "launch" folder.

Generating Octomaps

Octomaps can be generated most conveniently after the above procedure in a seperate step using the trajectory estimate from RGB-D SLAM. However, you will need to download the tgz packages from the benchmark homepage. You can then use a provided script in the RGBDSLAM package to create the octomaps:

rosrun rgbdslam generate_color_octomap_from_estimate.sh <directory-extracted-from-tgz> <trajectory-file>

E.g., to generate an octomap for the "teddy" sequence using the benchmark's ground truth use

rosrun rgbdslam generate_color_octomap_from_estimate.sh rgbd_dataset_freiburg1_teddy/ rgbd_dataset_freiburg1_teddy/groundtruth.txt

Assuming you followed the procedure above and have the trajectory estimate in ~/ros/rgbdslam/rgbd_benchmark/benchmark_data/SURF, the octomap from RGB-D SLAM's estimate could be created with the command

rosrun rgbdslam generate_color_octomap_from_estimate.sh rgbd_dataset_freiburg1_teddy/  ~/ros/rgbdslam/rgbd_benchmark/benchmark_data/SURF/rgbd_dataset_freiburg1_teddy/rgbd_dataset_freiburg1_teddy.bagafter1_optimization_estimate.txt

gt_octomap_teddy.png est_octomap_teddy.png

Left: Map from Ground Truth, Right: Map from Estimate

Wiki: rgbdslam_electric/evaluation (last edited 2016-12-06 00:07:22 by PeterNicholls)