Real-time dense visual SLAM system capable of capturing comprehensive dense globally consistent surfel-based maps of room scale environments explored using an RGB-D camera.
Please cite this work if you make use of our system in any of your own endeavors:
- ElasticFusion: Real-Time Dense SLAM and Light Source Estimation, T. Whelan, R. F. Salas-Moreno, B. Glocker, A. J. Davison and S. Leutenegger, IJRR '16
- ElasticFusion: Dense SLAM Without A Pose Graph, T. Whelan, S. Leutenegger, R. F. Salas-Moreno, B. Glocker and A. J. Davison, RSS '15
Ubuntu 22.04 on Xorg, NVIDIA drivers 510.73.05, CUDA driver 11.6, CUDA toolkit 11.5 (essentially whatever is in the Ubuntu repos).
sudo apt install -y cmake-qt-gui git build-essential libusb-1.0-0-dev libudev-dev openjdk-11-jdk freeglut3-dev libglew-dev libsuitesparse-dev zlib1g-dev libjpeg-dev
git clone https://github.com/mp3guy/ElasticFusion.git
cd ElasticFusion/
git submodule update --init
cd third-party/OpenNI2/
make -j8
cd ../Pangolin/
mkdir build
cd build
cmake .. -DEIGEN_INCLUDE_DIR=$HOME/ElasticFusion/third-party/Eigen/ -DBUILD_PANGOLIN_PYTHON=false
make -j8
cd ../../..
mkdir build
cd build/
cmake ..
There are two subprojects in the repo:
- The Core is the main engine which builds into a shared library that you can link into other projects and treat like an API.
- The Tools where the graphical interface used to run the system on either live sensor data or a logged data file lives.
The executable (ElasticFusion) can take a bunch of parameters when launching it from the command line. They are as follows:
- -cal : Loads a camera calibration file specified as fx fy cx cy.
- -l : Processes the specified .klg log file.
- -p : Loads ground truth poses to use instead of estimated pose.
- -c : Surfel confidence threshold (default 10).
- -d : Cutoff distance for depth processing (default 3m).
- -i : Relative ICP/RGB tracking weight (default 10).
- -ie : Local loop closure residual threshold (default 5e-05).
- -ic : Local loop closure inlier threshold (default 35000).
- -cv : Local loop closure covariance threshold (default 1e-05).
- -pt : Global loop closure photometric threshold (default 115).
- -ft : Fern encoding threshold (default 0.3095).
- -t : Time window length (default 200).
- -s : Frames to skip at start of log.
- -e : Cut off frame of log.
- -f : Flip RGB/BGR.
- -icl : Enable this if using the ICL-NUIM dataset (flips normals to account for negative focal length on that data).
- -o : Open loop mode.
- -rl : Enable relocalisation.
- -fs : Frame skip if processing a log to simulate real-time.
- -q : Quit when finished a log.
- -fo : Fast odometry (single level pyramid).
- -nso : Disables SO(3) pre-alignment in tracking.
- -r : Rewind and loop log forever.
- -ftf : Do frame-to-frame RGB tracking.
- -sc : Showcase mode (minimal GUI).
Essentially by default ./ElasticFusion will try run off an attached ASUS sensor live. You can provide a .klg log file instead with the -l parameter. You can capture .klg format logs using either Logger1 or Logger2.
The libefusion.so shared library which gets built by the Core is what you want to link against.
To then use the Core API, make sure to include the header file in your source file:
#include <ElasticFusion.h>
Initialise the static configuration parameters once somewhere at the start of your program:
Resolution::getInstance(640, 480);
Intrinsics::getInstance(528, 528, 320, 240);
Create an OpenGL context before creating an ElasticFusion object, as ElasticFusion uses OpenGL internally. You can do this whatever way you wish, using Pangolin is probably easiest given it's a dependency:
pangolin::Params windowParams;
windowParams.Set("SAMPLE_BUFFERS", 0);
windowParams.Set("SAMPLES", 0);
pangolin::CreateWindowAndBind("Main", 1280, 800, windowParams);
Make an ElasticFusion object and start using it:
ElasticFusion eFusion;
eFusion.processFrame(rgb, depth, timestamp, currentPose, weightMultiplier);
See the source code of MainController.cpp to see more usage.
We have provided a sample dataset which you can run easily with ElasticFusion for download here. Launch it as follows:
./ElasticFusion -l dyson_lab.klg
ElasticFusion is freely available for non-commercial use only. Full terms and conditions which govern its use are detailed here and in the LICENSE.txt file.
What are the hardware requirements?
A very fast nVidia GPU (3.5TFLOPS+), and a fast CPU (something like an i7). If you want to use a non-nVidia GPU you can rewrite the tracking code or substitute it with something else, as the rest of the pipeline is actually written in the OpenGL Shading Language.
How can I get performance statistics?
Download Stopwatch and run StopwatchViewer at the same time as ElasticFusion.
I ran a large dataset and got assert(graph.size() / 16 < MAX_NODES) failed
Currently there's a limit on the number of nodes in the deformation graph down to lazy coding (using a really wide texture instead of a proper 2D one). So we're bound by the maximum dimension of a texture, which is 16384 on modern cards/OpenGL. Either fix the code so this isn't a problem any more, or increase the modulo factor in Core/Shaders/sample.geom.
I have a nice new laptop with a good GPU but it's still slow
If your laptop is running on battery power the GPU will throttle down to save power, so that's unlikely to work (as an aside, Kintinuous will run at 30Hz on a modern laptop on battery power these days). You can try disabling SO(3) pre-alignment, enabling fast odometry, only using either ICP or RGB tracking and not both, running in open loop mode or disabling the tracking pyramid. All of these will cost you accuracy.
I saved a map, how can I view it?
Download Meshlab. Select Render->Shaders->Splatting.
The map keeps getting corrupted - tracking is failing - loop closures are incorrect/not working
Firstly, if you're running live and not processing a log file, ensure you're hitting 30Hz, this is important. Secondly, you cannot move the sensor extremely fast because this violates the assumption behind projective data association. In addition to this, you're probably using a primesense, which means you're suffering from motion blur, unsynchronised cameras and rolling shutter. All of these are aggravated by fast motion and hinder tracking performance.
If you're not getting loop closures and expecting some, pay attention to the inlier and residual graphs in the bottom right, these are an indicator of how close you are to a local loop closure. For global loop closures, you're depending on fern keyframe encoding to save you, which like all appearance-based place recognition methods, has its limitations.
Is there a ROS bridge/node?
No. The system relies on an extremely fast and tight coupling between the mapping and tracking on the GPU, which I don't believe ROS supports natively in terms of message passing.
This doesn't seem to work like it did in the videos/papers
A substantial amount of refactoring was carried out in order to open source this system, including rewriting a lot of functionality to avoid certain licenses and reduce dependencies. Although great care was taken during this process, it is possible that performance regressions were introduced and have not yet been discovered.