This repository is an open-source implementation of Direct Sparse Odometry algorithm generalized for fisheye cameras. A paper from the authors of DSO exists, which describes how this generalization could be done. However, no open-source implementation is provided. We plan to expand our work even further to support arbitrary multi-camera systems with little to no FoV intersection.
Here is a point cloud, generated by our algorithm, next to the ground truth cloud.
The following process was tested on clean Ubuntu 18.04
Firstly, you may need to install some required packages:
sudo apt install git g++ cmake
sudo apt install libgflags-dev libgoogle-glog-dev libceres-dev
sudo apt install libtbb-dev
sudo apt install libopencv-dev
Addititionally, if you want to see nice graphs of errors, trajectories and more, you will need Python 3 and Matplotlib. You will also need to install some Python 3 packages for provided scripts to work:
sudo apt install python3 python3-matplotlib python3-pandas python3-pip
sudo pip3 install numpy-quaternion
After that you can download and build the system with CMake (for best performance we recommend that you use RelWithDebInfo build configuration):
git clone https://bitbucket.org/slamgroup/dso/
cd dso
git submodule update --init --recursive
mkdir bin && cd bin
cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo
make
Most of the demos support --help
flag to show the detailed description of flags that could be used.
Multi-FoV dataset
Fisheye Multi-FoV is currently the main dataset for testing purposes. You can currently run the odometry to generate trajectory and point cloud. It needs the full dataset to be present, including ground truth poses and depths. The expected structure of the data to be provided:
/path/to/MultiFoV
├── data
| ├── img
| | ├── img0001_0.png
| | └── ...
| └── depth
| ├── img0001_0.depth
| └── ...
└── info
├── depthmaps.txt
├── groundtruth.txt
└── ...
To get the trajectory and point clouds you need the genply
demo. It requires that empty folders for general output, debug images and tracking residuals are present. The default ones are output/default
, output/default/debug
and output/default/track
respectively. By default genply
runs on the whole dataset (which takes lots of time!), so you may want to run only on its segment. For this you may use --start
and --count
options. Considering you are in the root of the repository and you have already built the system, all you need to do is
mkdir -p output/default/debug output/default/track
./samples/mfov/genply/genply /path/to/MultiFoV
Among the other stuff it generates output/points.ply
point cloud, which you can inspect, for example, with the MeshLab tool.
If you want to inspect the trajectory that is generated, you can do it with
python3 py/showtrack.py path/to/output/dir
triang
is a simple demo that shows Delaunay Triangulation (which is used in the initialization part of our system) of a random selection of points in the square. It can be run as simple as this:
./triang
selectpix
demonstrates the adaptive pixel selection algorithm on a video of your choice. It could be run with
./selectpix dir
where dir names a directory with video frames stored as jpg or png files. Frames should be ordered alphabetically.
- CMake - Cross-platform build system
- Eigen - Template library for linear algebra
- Sophus - Template implementation of geometrical Lie groups (SO(3), SE(3), etc.)
- GFlags - Command-line flag parsing library
- GLog - Logging library
- ceres-solver - Scalable library for solving optimization problems
- TBB - Framework for parallelization
- OpenCV - Open-source Computer Vision library
This project is licensed under the terms of the MIT license. For more information, please check the LICENSE.txt
file.