Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fetch upstream changes #1

Open
wants to merge 11 commits into
base: master
Choose a base branch
from
55 changes: 49 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,26 @@

Please refer to the **[ESVO Project Page](https://sites.google.com/view/esvo-project-page/home)** for more detailed information and for testing event data.

**Videos**

[![IMAGE ALT TEXT HERE](https://img.youtube.com/vi/3CPPs1gz04k/mqdefault.jpg)](https://www.youtube.com/watch?v=3CPPs1gz04k)   
[![IMAGE ALT TEXT HERE](https://img.youtube.com/vi/NByVeO4Ss5o/mqdefault.jpg)](https://www.youtube.com/watch?v=NByVeO4Ss5o)

### Related Publications

* **[Event-based Stereo Visual Odometry](https://arxiv.org/abs/2007.15548)**, *Yi Zhou, Guillermo Gallego, Shaojie Shen*, arXiv preprint 2020 (under review).
* **[Event-based Stereo Visual Odometry](https://arxiv.org/abs/2007.15548)**, *Yi Zhou, Guillermo Gallego, Shaojie Shen*, IEEE Transactions on Robotics (T-RO) 2021.

* **[Semi-dense 3D Reconstruction with a Stereo Event Camera](https://arxiv.org/abs/1807.07429)**, *Yi Zhou, Guillermo Gallego, Henri Rebecq, Laurent Kneip, Hongdong Li, Davide Scaramuzza*, ECCV 2018.


# 1. Installation

We have tested ESVO on Ubuntu 18.04.5 LTS + ROS melodic + gcc 5.5.0 + cmake (>=3.10), and Ubuntu 16.04 LTS + ROS kinetic + gcc 5.4.0 + cmake (>=3.10). For Ubuntu 16.04, you may need to upgrade your cmake.
We have tested ESVO on machines with the following configurations
* Ubuntu 18.04.5 LTS + ROS melodic + gcc 5.5.0 + cmake (>=3.10) + OpenCV 3.2
* Ubuntu 16.04 LTS + ROS kinetic + gcc 5.4.0 + cmake (>=3.10) + OpenCV 3.2
* Ubuntu 20.04 LTS + ROS Noetic + OpenCV 4

For Ubuntu 16.04, you may need to upgrade your cmake.

## 1.1 Driver Installation

Expand All @@ -40,7 +50,10 @@ The previous command should clone the the repositories into folders called *catk

You may need `autoreconf` to compile glog_catkin. To install `autoreconf`, run

$ sudo apt-get install autoreconf
$ sudo apt-get install autoconf

Note that above command may change on different version of Ubuntu.
Please refer to https://askubuntu.com/a/269423 for details.


**yaml-cpp** is only used for loading calibration parameters from yaml files:
Expand All @@ -67,7 +80,6 @@ run
$ catkin build esvo_time_surface esvo_core
$ source ~/catkin_ws/devel/setup.bash


# 2. Usage
To run the pipeline, you need to download rosbag files from the [ESVO Project Page](https://sites.google.com/view/esvo-project-page/home).

Expand Down Expand Up @@ -96,6 +108,19 @@ To save trajectories at anytime, go to another terminal and terminate the system

You need to set the path in `/cfg/tracking_xxx.yaml` to which the result file will be saved.

## 2.3 esvo_core/mvstereo
This module implements the mapper of ESVO and some other event-based mapping methods (e.g. [26], [45]).
As a multi-view stereo (MVS) pipeline, it assumes that poses are known as prior.
To launch the mapper, run

$ roslaunch esvo_core mvstereo_xxx.launch

This will launch two *esvo_time_surface nodes* (for left and right event cameras, respectively), and the mapping node simultaneously.
Then play the input (already downloaded) bag file by running

$ roslaunch esvo_time_surface [bag_name].launch

Note that only *rpg* and *upenn* datasets are applicable for this module because they come with the ground truth poses.

# 3. Parameters (Dynamic Reconfigure)
## Time Surface
Expand All @@ -113,6 +138,13 @@ for denoising the time surface.
maintained at each coordinate.

## Mapping
**Event Matching**
- `EM_Slice_Thickness`: Determines the thickness of the temporal slice (unit: sec).
- `EM_Time_THRESHOLD`: Temporal simultaneity threshold.
- `EM_EPIPOLAR_THRESHOLD`: Epipolar constraint threshold.
- `EM_TS_NCC_THRESHOLD`: Motion consistency threshold.
- `EM_NUM_EVENT_MATCHING`: Maximum number of events for event matching.

**Block Matching**
- `BM_half_slice_thickness` : Determines the thickness of the temporal slice (unit: sec).
- `BM_min_disparity` : Minimum searching distance for epipolar matching.
Expand Down Expand Up @@ -202,10 +234,21 @@ The event data fed to ESVO needs to be recorded at remarkbly higher streaming ra

For convenience we provide a number of bag files, which have been rewritten to meet above requirement. They can be downloaded from the [ESVO Project Page](https://sites.google.com/view/esvo-project-page/home).


# 6. License
ESVO is licensed under the GNU General Public License Version 3 (GPLv3), see http://www.gnu.org/licenses/gpl.html.

For commercial use, please contact Yi Zhou and Shaojie Shen.

Email addresses are available in the project page.
Email addresses are available in the project page.

# 7. Log
* **12/01/2021** Merge with Suman Ghosh's pull request.
This commit fixed the running issue on machines with **Ubuntu 20.04 + ROS Noetic + OpenCV 4**.
* **28/01/2021** We provide the independent mapping module of ESVO.
This module maybe useful for people who are interested in event-based multi-view stereo (MVS) methods,
which typically assume poses are known as prior knowledge.
Besides, methods in [26], [45] are also implemented for comparison purpose.
Please refer to `2.3 esvo_core/mvstereo`.
* **23/02/2021** ESVO was integrated into the modular iniVation DV software platform.
It runs at up to 200 fps on Jetson TX2, and is fully open-source.
Download here: https://lnkd.in/deuRKSK.
14 changes: 12 additions & 2 deletions esvo_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@ project(esvo_core)
# explicitly set std=c++14 to remove errors from pcl library
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
# SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")
set(CMAKE_CXX_FLAGS "-O3")

find_package(catkin_simple REQUIRED)
catkin_simple(ALL_DEPS_REQUIRED)

SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")

find_package(OpenCV REQUIRED)

###########
Expand All @@ -27,6 +27,7 @@ set(HEADERS
include/esvo_core/core/EventBM.h
include/esvo_core/core/RegProblemLM.h
include/esvo_core/core/RegProblemSolverLM.h
include/esvo_core/core/EventMatcher.h
include/esvo_core/optimization/OptimizationFunctor.h
include/esvo_core/container/CameraSystem.h
include/esvo_core/container/DepthPoint.h
Expand All @@ -50,6 +51,7 @@ set(SOURCES
src/core/EventBM.cpp
src/core/RegProblemLM.cpp
src/core/RegProblemSolverLM.cpp
src/core/EventMatcher.cpp
src/container/CameraSystem.cpp
src/container/DepthPoint.cpp
src/container/ResidualItem.cpp
Expand All @@ -70,3 +72,11 @@ cs_add_executable(esvo_Tracking src/esvo_TrackingNode.cpp
src/esvo_Tracking.cpp include/esvo_core/esvo_Tracking.h)
target_link_libraries(esvo_Tracking ${PROJECT_NAME}_LIB
${catkin_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp)

# Node esvo_MVS (newly added in branch "mvs")
cs_add_executable(esvo_MVStereo
src/esvo_MVStereoNode.cpp
src/esvo_MVStereo.cpp
include/esvo_core/esvo_MVStereo.h)
target_link_libraries(esvo_MVStereo ${PROJECT_NAME}_LIB
${catkin_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp)
32 changes: 32 additions & 0 deletions esvo_core/calib/dsec/zurich_city_04_a/left.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
image_width: 640
image_height: 480
camera_name: RPG_DSEC_Prophesee_Gen3.1M
camera_matrix:
rows: 3
cols: 3
data: [553.469, 0, 346.653,
0, 553.399, 216.521,
0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0935648, 0.194458, 7.64243e-05, 0.00195639]
rectification_matrix:
rows: 3
cols: 3
data: [0.999866, -0.00319364, 0.0160517,
0.00322964, 0.999992, -0.00221712,
-0.0160445, 0.00226867, 0.999869]
projection_matrix:
rows: 3
cols: 4
data: [534.094, 0, 335.446, 0,
0, 534.094, 223.233, 0,
0, 0, 1, 0]
T_right_left:
rows: 3
cols: 4
data: [0.999759, -0.0113618, 0.0187657, -0.599011,
0.0114448, 0.999925, -0.0043174, -0.00490041,
-0.0187153, -0.0187153, 0.999815, 0.0016045]
32 changes: 32 additions & 0 deletions esvo_core/calib/dsec/zurich_city_04_a/right.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
image_width: 640
image_height: 480
camera_name: RPG_DSEC_Prophesee_Gen3.1M
camera_matrix:
rows: 3
cols: 3
data: [552.182, 0, 336.874,
0, 551.445, 226.326,
0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0949368, 0.202115, 0.000582129, 0.00145529]
rectification_matrix:
rows: 3
cols: 3
data: [0.999963, 0.00818053, -0.00267849,
-0.0081745, 0.999964, 0.00225394,
0.00269683, -0.00223196, 0.999994]
projection_matrix:
rows: 3
cols: 4
data: [534.094, 0, 335.446, -319.94,
0, 534.094, 223.233, 0,
0, 0, 1, 0]
T_right_left:
rows: 3
cols: 4
data: [0.999759, -0.0113618, 0.0187657, -0.599011,
0.0114448, 0.999925, -0.0043174, -0.00490041,
-0.0187153, -0.0187153, 0.999815, 0.0016045]
21 changes: 15 additions & 6 deletions esvo_core/cfg/DVS_MappingStereo.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -5,26 +5,35 @@ from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

# for EventMatcher
gen.add("EM_TIME_THRESHOLD", double_t, 0, "EM_TIME_THRESHOLD", 0.0001, 0.000001, 0.001)
gen.add("EM_EPIPOLAR_THRESHOLD", double_t, 0, "EM_EPIPOLAR_THRESHOLD", 0.5, 0.1, 5)
gen.add("EM_TS_NCC_THRESHOLD", double_t, 0, "EM_TS_NCC_THRESHOLD", 0.1, 0.0, 1.0)
gen.add("EM_NUM_EVENT_MATCHING", int_t, 0, "EM_NUM_EVENT_MATCHING", 30000, 0, 100000)
gen.add("EM_PATCH_INTENSITY_THRESHOLD", int_t, 0, "EM_PATCH_INTENSITY_THRESHOLD", 125, 0, 255)
gen.add("EM_PATCH_VALID_RATIO", double_t, 0, "EM_PATCH_VALID_RATIO", 0.1, 0, 1.0)

# for Block Matcher
gen.add("BM_MAX_NUM_EVENTS_PER_MATCING", int_t, 0, "BM_MAX_NUM_EVENTS_PER_MATCING", 400, 1, 5000)
gen.add("BM_MAX_NUM_EVENTS_PER_MATCHING", int_t, 0, "BM_MAX_NUM_EVENTS_PER_MATCHING", 400, 1, 50000)
gen.add("BM_min_disparity", int_t, 0, "BM_min_disparity", 0, 0, 5)
gen.add("BM_max_disparity", int_t, 0, "BM_max_disparity", 40, 0, 50)
gen.add("BM_max_disparity", int_t, 0, "BM_max_disparity", 40, 0, 150)
gen.add("BM_step", int_t, 0, "BM_step", 2, 1, 5)
gen.add("BM_ZNCC_Threshold", double_t, 0, "BM_ZNCC_Threshold", 0.1, 0, 1.0)

# for esvo_Mapping
gen.add("invDepth_min_range", double_t, 0, "InvDepth_MIN_RANGE", 0.16, 0.0, 10.0)
gen.add("invDepth_max_range", double_t, 0, "InvDepth_MAX_RANGE", 2.0, 0.0, 10.0)

gen.add("residual_vis_threshold", double_t, 0, "Residual_VIS_THRESHOLD", 12, 0.0, 50)
gen.add("stdVar_vis_threshold", double_t, 0, "StdVariance_VIS_THRESHOLD", 0.12, 0.0, 3.0)
gen.add("residual_vis_threshold", double_t, 0, "Residual_VIS_THRESHOLD", 12, 0.0, 1000000)
gen.add("stdVar_vis_threshold", double_t, 0, "StdVariance_VIS_THRESHOLD", 0.12, 0.0, 10000000)

gen.add("age_max_range", int_t, 0, "Age_MAX_RANGE", 5, 0, 10)
gen.add("age_vis_threshold", int_t, 0, "Age_VIS_RANGE", 5, 0, 10)
gen.add("age_vis_threshold", int_t, 0, "Age_VIS_RANGE", 1, 0, 10)

gen.add("fusion_radius", int_t, 0, "fusion radius", 0, 0, 5)
gen.add("maxNumFusionFrames", int_t, 0, "Max Fusion Times", 0, 0, 100)
gen.add("PROCESS_EVENT_NUM", int_t, 0, "#processed event", 100, 0, 10000)
gen.add("maxNumFusionPoints", int_t, 0, "Max Fusion Points",5000, 1000, 20000)
gen.add("PROCESS_EVENT_NUM", int_t, 0, "#processed event", 100, 0, 100000)
gen.add("TS_HISTORY_LENGTH", int_t, 0, "time_surface history length", 100, 0, 300)
gen.add("mapping_rate_hz", int_t, 0, "mapping rate", 20, 1, 30)

Expand Down
38 changes: 38 additions & 0 deletions esvo_core/cfg/mapping/mapping_dsec.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
invDepth_min_range: 0.001
invDepth_max_range: 0.25
residual_vis_threshold: 30 #20 #30 #20 #20
stdVar_vis_threshold: 1 #0.1 #0.2
age_max_range: 10
age_vis_threshold: 1
fusion_radius: 1
FUSION_STRATEGY: CONST_FRAMES #"CONST_POINTS" # "CONST_FRAMES"
maxNumFusionFrames: 5 #40
maxNumFusionPoints: 20000 #8000 #3000
Denoising: False
SmoothTimeSurface: True #False
Regularization: True
bVisualizeGlobalPC: True
visualizeGPC_interval: 0.5 #2[second]
NumGPC_added_per_refresh: 10000
visualize_range: 30
PROCESS_EVENT_NUM: 10000 #20000
TS_HISTORY_LENGTH: 100
INIT_SGM_DP_NUM_THRESHOLD: 500
mapping_rate_hz: 20
# DepthProblemConfig
patch_size_X: 15 #15
patch_size_Y: 7 #7
LSnorm: Tdist #Tdist #Tdist #Tdist # l2
Tdist_nu: 2.182 #2.1897
Tdist_scale: 17.277 #16.6397
Tdist_stdvar: 59.763 #56.5347
RegularizationRadius: 20
RegularizationMinNeighbours: 32
RegularizationMinCloseNeighbours: 32
# EventBM parameters
BM_half_slice_thickness: 0.001
BM_min_disparity: 0
BM_max_disparity: 150
BM_step: 1
BM_ZNCC_Threshold: 0.1
BM_bUpDownConfiguration: False
2 changes: 1 addition & 1 deletion esvo_core/cfg/mapping/mapping_hkust.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ SmoothTimeSurface: False
Regularization: True
bVisualizeGlobalPC: True
visualizeGPC_interval: 1 # (unit: s)
NumGPC_added_oper_refresh: 1500
NumGPC_added_per_refresh: 1500
visualize_range: 2.5
PROCESS_EVENT_NUM: 1000
TS_HISTORY_LENGTH: 100
Expand Down
2 changes: 1 addition & 1 deletion esvo_core/cfg/mapping/mapping_rpg.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ SmoothTimeSurface: False
Regularization: True
bVisualizeGlobalPC: True
visualizeGPC_interval: 3
NumGPC_added_oper_refresh: 1000 #1500 #3000
NumGPC_added_per_refresh: 1000
visualize_range: 5.0
PROCESS_EVENT_NUM: 1000
TS_HISTORY_LENGTH: 100
Expand Down
2 changes: 1 addition & 1 deletion esvo_core/cfg/mapping/mapping_upenn.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ SmoothTimeSurface: False
Regularization: False
bVisualizeGlobalPC: True
visualizeGPC_interval: 1
NumGPC_added_oper_refresh: 3000
NumGPC_added_per_refresh: 3000
visualize_range: 5.0
PROCESS_EVENT_NUM: 1000
TS_HISTORY_LENGTH: 100
Expand Down
45 changes: 45 additions & 0 deletions esvo_core/cfg/mvstereo/mvstereo_rpg.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
invDepth_min_range: 0.2
invDepth_max_range: 2
residual_vis_threshold: 20
stdVar_vis_threshold: 0.015
age_max_range: 10
age_vis_threshold: 1
fusion_radius: 0
FUSION_STRATEGY: "CONST_FRAMES" #"CONST_FRAMES" or "CONST_POINTS"
maxNumFusionFrames: 40
maxNumFusionPoints: 5000
Denoising: True
SmoothTimeSurface: False
Regularization: True
PROCESS_EVENT_NUM: 1000
TS_HISTORY_LENGTH: 100
mapping_rate_hz: 20
# DepthProblemConfig
patch_size_X: 15
patch_size_Y: 7
LSnorm: Tdist #(Tdist or l2)
Tdist_nu: 2.1897
Tdist_scale: 16.6397
Tdist_stdvar: 56.5347
# Event Matcher (EM) parameters
EM_Slice_Thickness: 0.001
EM_Time_THRESHOLD: 0.0005
EM_EPIPOLAR_THRESHOLD: 1.0
EM_TS_NCC_THRESHOLD: 0.1
EM_NUM_EVENT_MATCHING: 3000
EM_PATCH_INTENSITY_THRESHOLD: 10
EM_PATCH_VALID_RATIO: 0.75
# EventBM parameters
BM_half_slice_thickness: 0.001
BM_min_disparity: 1
BM_max_disparity: 40
BM_step: 1
BM_ZNCC_Threshold: 0.1
BM_bUpDownConfiguration: False
# MVStereo Mode
MVStereoMode: 3
# PURE_EVENT_MATCHING //0 EM [26]
# PURE_BLOCK_MATCHING //1 BM
# EM_PLUS_ESTIMATION //2 EM [26] + nonlinear opt.
# BM_PLUS_ESTIMATION //3 ESVO's mapper
# SEMI_GLOBAL_MATCHING //4 [45]
Loading