├── .gitignore
├── README.md
├── Software_License_Agreement_TUB_dvs_mcemvs.pdf
├── cartesian3dgrid
├── CMakeLists.txt
├── include
│ └── cartesian3dgrid
│ │ ├── cartesian3dgrid.h
│ │ └── gaussianiir3d.h
├── package.xml
└── src
│ ├── cartesian3dgrid.cpp
│ ├── cartesian3dgrid_IO.cpp
│ ├── cartesian3dgrid_filter.cpp
│ └── gaussianiir3d.cpp
├── data
└── DSEC
│ ├── interlaken_00-odometry
│ └── pose.bag
│ ├── zurich_city_02-odometry
│ └── pose.bag
│ └── zurich_city_04-odometry
│ └── pose.bag
├── dependencies.yaml
├── docs
├── 2022_MCEVMS_poster.pdf
├── block_all.png
├── datasets.md
├── evaluation.md
├── examples.md
├── installation.md
├── mcemvs_thumbnail.jpg
└── running.md
└── mapper_emvs_stereo
├── CMakeLists.txt
├── cfg
├── DSEC
│ ├── interlaken_00_b_2
│ │ └── dsec.conf
│ └── zurich_04_a_full
│ │ └── dsec.conf
├── evimo2
│ └── evimo2.conf
├── hkust
│ └── hkust_lab.conf
├── rpg_eccv18
│ ├── boxes_edited
│ │ ├── AtHc
│ │ │ └── rpg_boxes_edited.conf
│ │ ├── AtHc_shuffled
│ │ │ └── rpg_boxes_edited.conf
│ │ ├── alg1
│ │ │ └── rpg_boxes_edited.conf
│ │ └── fusionfuncs
│ │ │ ├── alg1_AM
│ │ │ └── rpg_boxes_edited.conf
│ │ │ ├── alg1_GM
│ │ │ └── rpg_boxes_edited.conf
│ │ │ ├── alg1_HM
│ │ │ └── rpg_boxes_edited.conf
│ │ │ ├── alg1_RMS
│ │ │ └── rpg_boxes_edited.conf
│ │ │ ├── alg1_max
│ │ │ └── rpg_boxes_edited.conf
│ │ │ └── alg1_min
│ │ │ └── rpg_boxes_edited.conf
│ ├── monitor_edited
│ │ ├── AtHc
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ ├── AtHc_shuffled
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ ├── alg1
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ └── fusionfuncs
│ │ │ ├── alg1_AM
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ │ ├── alg1_GM
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ │ ├── alg1_HM
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ │ ├── alg1_RMS
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ │ ├── alg1_max
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ │ │ └── alg1_min
│ │ │ └── rpg_monitor_edited_fixedts.conf
│ └── reader
│ │ └── alg1
│ │ └── rpg_reader_fixedts.conf
├── tumvie
│ ├── bike-easy-3_full
│ │ └── tum-vie.conf
│ ├── bike-easy-4_full
│ │ └── tum-vie.conf
│ ├── bike-easy-5_full
│ │ └── tum-vie.conf
│ ├── desk2_full
│ │ └── tum-vie.conf
│ ├── mocap-1d-trans_full
│ │ └── tum-vie.conf
│ ├── mocap-3d-trans_full
│ │ └── tum-vie.conf
│ ├── running-easy-0_full
│ │ └── tum-vie.conf
│ ├── running-easy-1_full
│ │ └── tum-vie.conf
│ └── skate-easy-1_full
│ │ └── tum-vie.conf
└── upenn_mvsec
│ ├── mvsec_flying1_full
│ ├── AcAt
│ │ └── flying1.conf
│ ├── AcHt
│ │ └── flying1.conf
│ ├── AtHc
│ │ └── flying1.conf
│ ├── AtHc_shuffled
│ │ └── flying1.conf
│ ├── HcHt
│ │ └── flying1.conf
│ └── alg1
│ │ └── flying1.conf
│ ├── mvsec_flying2_full
│ ├── AcAt
│ │ └── flying2.conf
│ ├── AcHt
│ │ └── flying2.conf
│ ├── AtHc
│ │ └── flying2.conf
│ ├── AtHc_shuffled
│ │ └── flying2.conf
│ ├── HcHt
│ │ └── flying2.conf
│ └── norm_max_c14
│ │ └── flying2.conf
│ └── mvsec_flying3_full
│ ├── AcAt
│ └── flying3.conf
│ ├── AcHt
│ └── flying3.conf
│ ├── AtHc
│ └── flying3.conf
│ ├── AtHc_shuffled
│ └── flying3.conf
│ ├── HcHt
│ └── flying3.conf
│ └── norm_max_c14
│ └── flying3.conf
├── include
└── mapper_emvs_stereo
│ ├── calib.hpp
│ ├── data_loading.hpp
│ ├── depth_vector.hpp
│ ├── geometry_utils.hpp
│ ├── mapper_emvs_stereo.hpp
│ ├── median_filtering.hpp
│ ├── process1.hpp
│ ├── process2.hpp
│ ├── process5.hpp
│ ├── trajectory.hpp
│ └── utils.hpp
├── launch
└── rpg_calib_info.launch
├── package.xml
├── scripts
├── depth_metrics.py
├── evaluate_mcemvs_dsec.py
├── mocap_txt2bag.py
├── precision_completeness.py
├── visualize_dsi_slices.py
├── visualize_dsi_volume.py
└── visualize_pointcloud.py
└── src
├── calib.cpp
├── data_loading.cpp
├── main.cpp
├── mapper_emvs_stereo.cpp
├── median_filtering.cpp
├── process1.cpp
├── process2.cpp
├── process5.cpp
└── utils.cpp
/.gitignore:
--------------------------------------------------------------------------------
1 | *.user
2 | mapper_emvs_stereo/experiments/
3 | mapper_emvs_stereo/*.png
4 | mapper_emvs_stereo/*.npy
5 | mapper_emvs_stereo/*.pcd
6 | .idea
7 |
8 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # MC-EMVS: Multi-Camera Event-based Multi-View Stereo
2 | This is the code for the journal paper [**Multi-Event-Camera Depth Estimation and Outlier Rejection by Refocused Events Fusion**](https://doi.org/10.1002/aisy.202200221), also known as **MC-EMVS: Multi-Camera Event-based Multi-View Stereo**,
3 | by [Suman Ghosh](https://www.linkedin.com/in/suman-ghosh-a8762576/) and [Guillermo Gallego](https://sites.google.com/view/guillermogallego), published at Advanced Intelligent Systems.
4 |
5 |
6 | [Paper](https://arxiv.org/pdf/2207.10494) | [Video](https://youtu.be/o7Bxg9XlHmg) | [Poster](/docs/2022_MCEVMS_poster.pdf)
7 |
8 |
9 | [](https://youtu.be/o7Bxg9XlHmg)
10 |
11 | If you use this work in your research, please cite it as follows:
12 |
13 | ```bibtex
14 | @article{Ghosh22aisy,
15 | author = {Ghosh, Suman and Gallego, Guillermo},
16 | title = {Multi-Event-Camera Depth Estimation and Outlier Rejection by Refocused Events Fusion},
17 | journal = {Advanced Intelligent Systems},
18 | year = {2022},
19 | doi = {10.1002/aisy.202200221}
20 | }
21 | ```
22 |
23 | ## Data Processing Pipeline
24 |
25 |
26 | 
27 |
28 | ### Input
29 | * Events from multiple cameras
30 | * Pose of camera rig
31 | * Camera calibration (intrinsic, extrinsic, hand-eye) parameters
32 |
33 | ### Output
34 | * Depth map
35 | * Confidence map
36 | * Point cloud
37 | * Intermediate ray density maps / Disparity Space Images (DSI)
38 |
39 | ## Code
40 | * [Installation instructions](docs/installation.md)
41 | * [Running the code with various configurations](docs/running.md)
42 | * [Datasets used](docs/datasets.md)
43 | * [Running Examples](docs/examples.md)
44 | * [Evaluation scripts](docs/evaluation.md)
45 |
46 |
47 | ## License
48 |
49 | The license is available [here](Software_License_Agreement_TUB_dvs_mcemvs.pdf).
50 |
51 | Follow-up works
52 | -------
53 | * **[Event-based Stereo Depth Estimation: A Survey](https://arxiv.org/pdf/2409.17680)**
54 | * **[ES-PTAM: Event-based Stereo Parallel Tracking and Mapping](https://github.com/tub-rip/ES-PTAM)**
55 |
56 | Additional Resources on Event-based Vision
57 | -------
58 | * [Research page (TU Berlin RIP lab)](https://sites.google.com/view/guillermogallego/research/event-based-vision)
59 | * [Course at TU Berlin](https://sites.google.com/view/guillermogallego/teaching/event-based-robot-vision)
60 | * [Event-based Vision: A Survey](http://rpg.ifi.uzh.ch/docs/EventVisionSurvey.pdf)
61 | * [List of Resources](https://github.com/uzh-rpg/event-based_vision_resources)
62 |
--------------------------------------------------------------------------------
/Software_License_Agreement_TUB_dvs_mcemvs.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/Software_License_Agreement_TUB_dvs_mcemvs.pdf
--------------------------------------------------------------------------------
/cartesian3dgrid/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | project(cartesian3dgrid)
2 | set(CMAKE_CXX_STANDARD 14)
3 | set(CMAKE_CXX_STANDARD_REQUIRED ON)
4 | cmake_minimum_required(VERSION 2.8.3)
5 |
6 | find_package(catkin_simple REQUIRED)
7 | catkin_simple(ALL_DEPS_REQUIRED)
8 |
9 | set(CMAKE_BUILD_TYPE RelWithDebInfo) # Release, RelWithDebInfo
10 | set(CMAKE_CXX_FLAGS "-O3 ${CMAKE_CXX_FLAGS} -fopenmp")
11 |
12 | file(GLOB SOURCE_FILES src/cartesian3dgrid.cpp
13 | src/cartesian3dgrid_IO.cpp)
14 |
15 | cs_add_library(${PROJECT_NAME} ${SOURCE_FILES} ${HEADER_FILES})
16 | target_link_libraries(${PROJECT_NAME})
17 |
18 | #target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
19 |
20 | cs_export()
21 |
--------------------------------------------------------------------------------
/cartesian3dgrid/include/cartesian3dgrid/cartesian3dgrid.h:
--------------------------------------------------------------------------------
1 | /*
2 | * \file cartesian3dgrid.h
3 | * \brief header file for handling 3d volume
4 | * \author (1) Suman Ghosh
5 | * \date 2022-09-01
6 | * \author (2) Guillermo Gallego
7 | * \date 2022-09-01
8 | * Copyright/Rights of Use:
9 | * 2022, Technische Universität Berlin
10 | * Prof. Guillermo Gallego
11 | * Robotic Interactive Perception
12 | * Marchstrasse 23, Sekr. MAR 5-5
13 | * 10587 Berlin, Germany
14 | */
15 |
16 | #pragma once
17 |
18 | #include
19 | #include
20 | #include
21 |
22 | class Grid3D
23 | {
24 | public:
25 | Grid3D();
26 | Grid3D(const unsigned int dimX, const unsigned int dimY, const unsigned int dimZ);
27 | ~Grid3D();
28 |
29 | void allocate(const unsigned int dimX, const unsigned int dimY, const unsigned int dimZ);
30 | void deallocate();
31 |
32 | void printInfo() const;
33 |
34 | // The 3D data is stored in a 1D array that is ordered such that
35 | // volume[x + dimX*(y + dimY*z)] = data value at (x,y,z).
36 |
37 | // Accessing elements of the grid:
38 |
39 | // At integer location
40 | inline float getGridValueAt(const unsigned int ix, const unsigned int iy, const unsigned int iz) const
41 | {
42 | return data_array_.at(ix + size_[0]*(iy + size_[1]*iz));
43 | }
44 |
45 | inline float getGridValueAt(const unsigned int p) const
46 | {
47 | return data_array_.at(p);
48 | }
49 |
50 | inline void accumulateGridValueAt(const unsigned int p, const float fval)
51 | {
52 | data_array_.at(p) += fval;
53 | }
54 |
55 | inline void setGridValueAt(const unsigned int p, const float fval)
56 | {
57 | data_array_.at(p) = fval;
58 | }
59 |
60 | // At floating point location within a Z slice. Bilinear interpolation or voting.
61 | inline void accumulateGridValueAt(const float x_f, const float y_f, float* grid);
62 |
63 | // FIXME: The following voxel-wise operations do not use parallelization yet
64 | inline void addTwoGrids(const Grid3D grid2)
65 | {
66 | for (int p = 0; p < numCells_; p++)
67 | {
68 | data_array_.at(p) += grid2.data_array_.at(p);
69 | }
70 | }
71 |
72 | inline void addInverseOfTwoGrids(const Grid3D grid2, const float eps=1e-2)
73 | {
74 | for (int p = 0; p < numCells_; p++)
75 | {
76 | data_array_.at(p) = data_array_.at(p) + 1.0f/(eps + grid2.data_array_.at(p));
77 | }
78 | }
79 |
80 | inline void computeHMfromSumOfInv(int n)
81 | {
82 | for (int p = 0; p < numCells_; p++)
83 | {
84 | data_array_.at(p) = (float)n /(data_array_.at(p));
85 | }
86 | }
87 | inline void computeAMfromSum(int n)
88 | {
89 | for (int p = 0; p < numCells_; p++)
90 | {
91 | data_array_.at(p) = data_array_.at(p)/(float)n;
92 | }
93 | }
94 |
95 | inline void subtractTwoGrids(const Grid3D grid2)
96 | {
97 | for (int p = 0; p < numCells_; p++)
98 | {
99 | data_array_.at(p) -= grid2.data_array_.at(p);
100 | }
101 | }
102 |
103 | inline void ratioTwoGrids(const Grid3D grid2, const float eps=1e-1)
104 | {
105 | for (int p = 0; p < numCells_; p++)
106 | {
107 | data_array_.at(p) /= fabs(grid2.data_array_.at(p)) + eps;
108 | }
109 | }
110 |
111 | inline void minTwoGrids(const Grid3D grid2)
112 | {
113 | for (int p = 0; p < numCells_; p++)
114 | {
115 | data_array_.at(p) = std::min(data_array_.at(p), grid2.data_array_.at(p));
116 | }
117 | }
118 |
119 | inline void harmonicMeanTwoGrids(const Grid3D grid2, const float eps=1e-1)
120 | {
121 | for (int p = 0; p < numCells_; p++)
122 | {
123 | float prod = data_array_.at(p) * grid2.data_array_.at(p);
124 | float sum = data_array_.at(p) + grid2.data_array_.at(p);
125 | data_array_.at(p) = 2*prod / (sum + eps);
126 | }
127 | }
128 |
129 | // allows for recursive application by stating number of maps to fuse
130 | inline void harmonicMeanTwoGrids(const Grid3D grid2, int n, const float eps=1e-1)
131 | {
132 | for (int p = 0; p < numCells_; p++)
133 | {
134 | float a = data_array_.at(p)/(float)(n-1);
135 | float prod = a * grid2.data_array_.at(p);
136 | float sum = a + grid2.data_array_.at(p);
137 | data_array_.at(p) = n*prod / (sum + eps);
138 | }
139 | }
140 |
141 | inline void rmsTwoGrids(const Grid3D grid2)
142 | {
143 | for (int p = 0; p < numCells_; p++)
144 | {
145 | float ms = 0.5*(pow(data_array_.at(p), 2) + pow(grid2.data_array_.at(p), 2));
146 | data_array_.at(p) = sqrt(ms);
147 | }
148 | }
149 |
150 | inline void geometricMeanTwoGrids(const Grid3D grid2)
151 | {
152 | for (int p = 0; p < numCells_; p++)
153 | {
154 | data_array_.at(p) = std::sqrt(data_array_.at(p) * grid2.data_array_.at(p));
155 | }
156 | }
157 |
158 | inline void arithmeticMeanTwoGrids(const Grid3D grid2)
159 | {
160 | for (int p = 0; p < numCells_; p++)
161 | {
162 | data_array_.at(p) = 0.5 * (data_array_.at(p) + grid2.data_array_.at(p));
163 | }
164 | }
165 |
166 | inline void quadraticMeanTwoGrids(const Grid3D grid2)
167 | {
168 | for (int p = 0; p < numCells_; p++)
169 | {
170 | float u = data_array_.at(p);
171 | float v = grid2.data_array_.at(p);
172 | data_array_.at(p) = std::sqrt( 0.5 * (u*u + v*v) );
173 | }
174 | }
175 |
176 | inline void cubicMeanTwoGrids(const Grid3D grid2)
177 | {
178 | for (int p = 0; p < numCells_; p++)
179 | {
180 | float u = data_array_.at(p);
181 | float v = grid2.data_array_.at(p);
182 | data_array_.at(p) = std::cbrt( 0.5 * (u*u*u + v*v*v) );
183 | }
184 | }
185 |
186 | inline void maxTwoGrids(const Grid3D grid2)
187 | {
188 | for (int p = 0; p < numCells_; p++)
189 | {
190 | data_array_.at(p) = std::max(data_array_.at(p), grid2.data_array_.at(p));
191 | }
192 | }
193 |
194 |
195 | inline void accumulateZSliceAt(const unsigned int iz, const cv::Mat& img)
196 | {
197 | for(unsigned int iy=0; iy < img.rows; iy++)
198 | {
199 | for(unsigned int ix=0; ix < img.cols; ix++)
200 | {
201 | data_array_.at(ix + size_[0]*(iy + size_[1]*iz)) += img.at(iy,ix);
202 | }
203 | }
204 | }
205 |
206 | cv::Mat getSlice(const unsigned int sliceIdx, const unsigned int dimIdx) const;
207 | void collapseMaxZSlice(cv::Mat* max_val, cv::Mat* max_pos) const;
208 | void collapseMinZSlice(cv::Mat* min_val, cv::Mat* min_pos) const;
209 |
210 | void collapseZSliceByGradMag(cv::Mat* confidence, cv::Mat* depth_cell_indices, int half_patchsize=1);
211 | void collapseZSliceByLaplacianMag(cv::Mat* confidence, cv::Mat* depth_cell_indices);
212 | void collapseZSliceByDoG(cv::Mat* confidence, cv::Mat* depth_cell_indices);
213 | void collapseZSliceByLocalVar(cv::Mat* confidence, cv::Mat* depth_cell_indices);
214 | void collapseZSliceByLocalMeanSquare(cv::Mat* confidence, cv::Mat* depth_cell_indices);
215 |
216 | void computeLocalFocusInPlace(int focus_method);
217 | void computeLocalMeanSquareInPlace();
218 | void computeLocalVarInPlace();
219 |
220 | // Statistics
221 | double computeMeanSquare() const;
222 | void getMinMax(float* min_val, float* max_val, unsigned long* min_pos=NULL, unsigned long* max_pos=NULL) const;
223 |
224 | void resetGrid();
225 |
226 | // Output
227 | int writeGridNpy(const char szFilename[]) const;
228 | void imwriteSlices(const char prefix[], const unsigned int dimIdx, bool normalize_by_minmax=true) const;
229 |
230 | void getDimensions(int* dimX, int* dimY, int* dimZ) const
231 | {
232 | *dimX = size_[0];
233 | *dimY = size_[1];
234 | *dimZ = size_[2];
235 | }
236 |
237 | float* getPointerToSlice(int layer)
238 | {
239 | return &data_array_.data()[layer * size_[0] * size_[1]];
240 | }
241 |
242 | private:
243 | std::vector data_array_;
244 | unsigned int numCells_;
245 | unsigned int size_[3];
246 |
247 | };
248 |
249 |
250 | // Function implementation
251 |
252 | // Bilinear voting within a Z-slice, if point (x,y) is given as float
253 | inline void Grid3D::accumulateGridValueAt(const float x_f, const float y_f, float* grid)
254 | {
255 | if (x_f >= 0.f && y_f >= 0.f)
256 | {
257 | const int x = x_f, y = y_f;
258 | if (x+1 < size_[0] &&
259 | y+1 < size_[1])
260 | {
261 | float* g = grid + x + y * size_[0];
262 | const float fx = x_f - x,
263 | fy = y_f - y,
264 | fx1 = 1.f - fx,
265 | fy1 = 1.f - fy;
266 |
267 | g[0] += fx1*fy1;
268 | g[1] += fx*fy1;
269 | g[size_[0]] += fx1*fy;
270 | g[size_[0]+1] += fx*fy;
271 | }
272 | }
273 | }
274 |
--------------------------------------------------------------------------------
/cartesian3dgrid/include/cartesian3dgrid/gaussianiir3d.h:
--------------------------------------------------------------------------------
1 | #pragma once
2 | #include "cartesian3dgrid.h"
3 |
4 | /**
5 | * \file gaussianiir3d.h
6 | * \brief Fast 3D Gaussian convolution IIR approximation
7 | * \author Pascal Getreuer
8 | *
9 | * Copyright (c) 2011, Pascal Getreuer
10 | * All rights reserved.
11 | *
12 | * This program is free software: you can redistribute it and/or modify it
13 | * under, at your option, the terms of the GNU General Public License as
14 | * published by the Free Software Foundation, either version 3 of the
15 | * License, or (at your option) any later version, or the terms of the
16 | * simplified BSD license.
17 | *
18 | * You should have received a copy of these licenses along with this program.
19 | * If not, see and
20 | * .
21 | */
22 |
23 | void gaussianiir3d(float *volume, long width, long height, long depth, float sigma, int numsteps);
24 |
25 | void gaussianiir3d(float *volume, long width, long height, long depth, float sigma_x, float sigma_y, float sigma_z, int numsteps);
26 |
27 | void smoothInPlace(const float sigma=1.f);
28 | void smoothInPlaceIIR3D(const float sigma_x=1.f, const float sigma_y=1.f, const float sigma_z=1.f);
29 | void laplacianInPlace();
30 |
--------------------------------------------------------------------------------
/cartesian3dgrid/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | cartesian3dgrid
4 | 0.0.0
5 | Cartesian 3D grid
6 | Guillermo Gallego
7 |
8 | see LICENSE
9 |
10 | catkin
11 | catkin_simple
12 |
13 | cv_bridge
14 | cnpy_catkin
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/cartesian3dgrid/src/cartesian3dgrid.cpp:
--------------------------------------------------------------------------------
1 | /*
2 | * \file cartesian3dgrid.cpp
3 | * \brief utility functions for handling 3D volumes
4 | * \author (1) Suman Ghosh
5 | * \date 2022-09-01
6 | * \author (2) Guillermo Gallego
7 | * \date 2022-09-01
8 | * Copyright/Rights of Use:
9 | * 2022, Technische Universität Berlin
10 | * Prof. Guillermo Gallego
11 | * Robotic Interactive Perception
12 | * Marchstrasse 23, Sekr. MAR 5-5
13 | * 10587 Berlin, Germany
14 | */
15 |
16 | #include "../include/cartesian3dgrid/cartesian3dgrid.h"
17 |
18 | #include
19 | #include
20 | #include
21 | #include
22 |
23 |
24 | Grid3D::Grid3D()
25 | {
26 | deallocate();
27 | }
28 |
29 |
30 | Grid3D::Grid3D(const unsigned int dimX, const unsigned int dimY, const unsigned int dimZ)
31 | {
32 | deallocate();
33 | allocate(dimX,dimY,dimZ);
34 | }
35 |
36 |
37 | void Grid3D::allocate(const unsigned int dimX, const unsigned int dimY, const unsigned int dimZ)
38 | {
39 | size_[0] = dimX;
40 | size_[1] = dimY;
41 | size_[2] = dimZ;
42 | numCells_ = size_[0]*size_[1]*size_[2];
43 | data_array_.resize(numCells_);
44 | resetGrid();
45 | }
46 |
47 |
48 | Grid3D::~Grid3D()
49 | {
50 | deallocate();
51 | }
52 |
53 |
54 | void Grid3D::deallocate()
55 | {
56 | size_[0] = size_[1] = size_[2] = 0;
57 | data_array_.clear();
58 | }
59 |
60 |
61 | void Grid3D::printInfo() const
62 | {
63 | std::cout << "Grid3D Dimensions: " << "(" << size_[0] << "," << size_[1] << "," << size_[2] << ")" << std::endl;
64 | std::cout << "Grid3D Data_array size: " << data_array_.size() << std::endl;
65 | }
66 |
67 | void Grid3D::resetGrid()
68 | {
69 | std::fill(data_array_.begin(), data_array_.end(), 0.f);
70 | }
71 |
72 | cv::Mat Grid3D::getSlice(const unsigned int sliceIdx, const unsigned int dimIdx) const
73 | {
74 | cv::Mat slice;
75 |
76 | // simplest way
77 | if (dimIdx==0)
78 | {
79 | // X-slice
80 | unsigned int u_size = size_[2], // Z acts as X-axis
81 | v_size = size_[1];
82 | slice = cv::Mat(v_size,u_size,CV_32FC1);
83 | for(unsigned int u=0; u(v,u) = getGridValueAt(sliceIdx,v,u);
86 | }
87 | else if (dimIdx==1)
88 | {
89 | // Y-slice
90 | unsigned int u_size = size_[2], // Z acts as X-axis
91 | v_size = size_[0];
92 | slice = cv::Mat(v_size,u_size,CV_32FC1);
93 | for(unsigned int u=0; u(v,u) = getGridValueAt(v,sliceIdx,u);
96 | }
97 | else if (dimIdx==2)
98 | {
99 | // Z-slice
100 | unsigned int u_size = size_[0],
101 | v_size = size_[1];
102 | slice = cv::Mat(v_size,u_size,CV_32FC1); // (y,x) as in images
103 | for(unsigned int v=0; v(v,u) = getGridValueAt(u,v,sliceIdx);
106 | }
107 | else
108 | {
109 | std::cout << "ERROR. dimIdx should be 0, 1 or 2" << std::endl;
110 | }
111 |
112 | return slice;
113 | }
114 |
115 | void Grid3D::collapseMaxZSlice(cv::Mat* max_val, cv::Mat* max_pos_idx) const
116 | {
117 | // Z-slice
118 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
119 | *max_val = cv::Mat(v_size,u_size, CV_32FC1); // (y,x) as in images
120 | *max_pos_idx = cv::Mat(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
121 |
122 | std::vector grid_vals_vec(w_size);
123 | for(unsigned int v=0; v(v,u) = *max;
134 | (*max_pos_idx).at(v,u) = std::distance(std::begin(grid_vals_vec), max);
135 | }
136 | }
137 | }
138 |
139 | void Grid3D::collapseMinZSlice(cv::Mat* max_val, cv::Mat* max_pos_idx) const
140 | {
141 | // Z-slice
142 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
143 | *max_val = cv::Mat(v_size,u_size, CV_32FC1); // (y,x) as in images
144 | *max_pos_idx = cv::Mat(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
145 |
146 | std::vector grid_vals_vec(w_size);
147 | for(unsigned int v=0; v(v,u) = *max;
158 | (*max_pos_idx).at(v,u) = std::distance(std::begin(grid_vals_vec), max);
159 | }
160 | }
161 | }
162 |
163 |
164 | double Grid3D::computeMeanSquare() const
165 | {
166 | double result = 0.;
167 | for (int i=0; i(y,x); // Causes double edges
224 |
225 | cv::Mat patch = grad_mag(cv::Rect(x-half_patchsize, y-half_patchsize, patch_size, patch_size)); //.mul(gaussian_kernel_2d);
226 | float focus = cv::mean(patch)[0];
227 |
228 | // Select maximum focus value along the optical ray
229 | if(focus > confidence->at(y,x))
230 | {
231 | confidence->at(y,x) = focus; // max focus along optical ray
232 | depth_cell_indices->at(y,x) = k;
233 | }
234 | }
235 | }
236 | }
237 |
238 | // Return gradient magnitude instead of its square
239 | cv::sqrt(*confidence, *confidence);
240 | }
241 |
242 |
243 | void Grid3D::collapseZSliceByLaplacianMag(cv::Mat* confidence, cv::Mat* depth_cell_indices)
244 | {
245 | // Z-slice
246 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
247 | *confidence = cv::Mat::zeros(v_size,u_size, CV_32FC1); // (y,x) as in images
248 | *depth_cell_indices = cv::Mat::zeros(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
249 |
250 | for(unsigned int k=0; k(y,x);
268 |
269 | // Select maximum focus value along the optical ray
270 | if(focus > confidence->at(y,x))
271 | {
272 | confidence->at(y,x) = focus; // max focus along optical ray
273 | depth_cell_indices->at(y,x) = k;
274 | }
275 | }
276 | }
277 | }
278 |
279 | // Return gradient magnitude instead of its square
280 | cv::sqrt(*confidence, *confidence);
281 | }
282 |
283 |
284 | void Grid3D::collapseZSliceByDoG(cv::Mat* confidence, cv::Mat* depth_cell_indices)
285 | {
286 | // Z-slice
287 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
288 | *confidence = cv::Mat::zeros(v_size,u_size, CV_32FC1); // (y,x) as in images
289 | *depth_cell_indices = cv::Mat::zeros(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
290 |
291 | // Compute DoG filtered image
292 | const double sigma = 0.5; // 1.0
293 |
294 | //const double sigma2 = sigma * 3.0; // DoG
295 | const double sigma2 = sigma * 1.6; // LoG
296 |
297 | for(unsigned int k=0; k(y,x));
317 |
318 | // Select maximum focus value along the optical ray
319 | if(focus > confidence->at(y,x))
320 | {
321 | confidence->at(y,x) = focus; // max focus along optical ray
322 | depth_cell_indices->at(y,x) = k;
323 | }
324 | }
325 | }
326 | }
327 | }
328 |
329 |
330 | void Grid3D::collapseZSliceByLocalVar(cv::Mat* confidence, cv::Mat* depth_cell_indices)
331 | {
332 | // Z-slice
333 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
334 | *confidence = cv::Mat::zeros(v_size,u_size, CV_32FC1); // (y,x) as in images
335 | *depth_cell_indices = cv::Mat::zeros(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
336 |
337 | const double sigma = 0.5;
338 |
339 | for(unsigned int k=0; k(y,x));
359 |
360 | // Select maximum focus value along the optical ray
361 | if(focus > confidence->at(y,x))
362 | {
363 | confidence->at(y,x) = focus; // max focus along optical ray
364 | depth_cell_indices->at(y,x) = k;
365 | }
366 | }
367 | }
368 | }
369 |
370 | // Return std instead of variance
371 | //cv::sqrt(*confidence, *confidence);
372 | }
373 |
374 |
375 | void Grid3D::collapseZSliceByLocalMeanSquare(cv::Mat* confidence, cv::Mat* depth_cell_indices)
376 | {
377 | // Z-slice
378 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
379 | *confidence = cv::Mat::zeros(v_size,u_size, CV_32FC1); // (y,x) as in images
380 | *depth_cell_indices = cv::Mat::zeros(v_size,u_size, CV_8U); // WARNING: Max 256 depth layers
381 |
382 | const double sigma = 0.5;
383 |
384 | for(unsigned int k=0; k(y,x);
401 |
402 | // Select maximum focus value along the optical ray
403 | if(focus > confidence->at(y,x))
404 | {
405 | confidence->at(y,x) = focus; // max focus along optical ray
406 | depth_cell_indices->at(y,x) = k;
407 | }
408 | }
409 | }
410 | }
411 |
412 | // Return sqrt of MS
413 | //cv::sqrt(*confidence, *confidence);
414 | }
415 |
416 |
417 | void Grid3D::computeLocalFocusInPlace(int focus_method)
418 | {
419 | switch (focus_method)
420 | {
421 | case 1:
422 | computeLocalMeanSquareInPlace();
423 | break;
424 | default:
425 | computeLocalVarInPlace();
426 | break;
427 | }
428 | }
429 |
430 |
431 | void Grid3D::computeLocalVarInPlace()
432 | {
433 | // Z-slice
434 | unsigned int u_size = size_[0], v_size = size_[1], w_size = size_[2];
435 |
436 | const double sigma = 0.5;
437 |
438 | #pragma omp parallel for
439 | for(unsigned int k=0; k
19 | #include
20 | #include
21 | #include
22 | #include
23 | #include
24 |
25 | #include
26 |
27 |
28 | //--------------------- Output for Numpy -----------------------------------------
29 |
30 | int Grid3D::writeGridNpy(const char filename[]) const
31 | {
32 | cnpy::npy_save(std::string(filename),
33 | &data_array_[0],
34 | {size_[2], size_[1], size_[0]}, "w");
35 | return 0;
36 | }
37 |
38 |
39 | void Grid3D::imwriteSlices(const char prefix[], const unsigned int dimIdx, bool normalize_by_minmax) const
40 | {
41 | // Option: write images normalizing by the maximum value over grid
42 | float min, max, range;
43 | if (normalize_by_minmax)
44 | {
45 | auto it = std::minmax_element(std::begin(data_array_), std::end(data_array_));
46 | min = *it.first;
47 | max = *it.second;
48 | range = max - min;
49 | //std::cout << "Min value " << min << std::endl;
50 | //std::cout << "Max value " << max << std::endl;
51 | }
52 |
53 | #pragma omp parallel for
54 | for (int idx_slice = 0; idx_slice < size_[dimIdx]; idx_slice++)
55 | {
56 | // Get slice
57 | cv::Mat slice_img = getSlice(idx_slice, dimIdx);
58 |
59 | // Write slice to disk
60 | std::stringstream ss;
61 | ss << std::string(prefix) << std::setfill('0') << std::setw(3) << idx_slice << ".png";
62 | cv::Mat slice_u;
63 | if (normalize_by_minmax)
64 | {
65 | // All slices are normalized using the range
66 | slice_img = (slice_img - min) / range;
67 | slice_img.convertTo(slice_u,CV_8UC1,255);
68 | }
69 | else
70 | {
71 | // Each slice is normalized independently from the rest
72 | cv::normalize(slice_img, slice_u, 0, 255, cv::NORM_MINMAX, CV_8UC1);
73 | }
74 | imwrite(ss.str(),slice_u);
75 | }
76 | }
77 |
--------------------------------------------------------------------------------
/cartesian3dgrid/src/cartesian3dgrid_filter.cpp:
--------------------------------------------------------------------------------
1 | #include "cartesian3dgrid/cartesian3dgrid.h"
2 |
3 | #include
4 | #include
5 |
6 | #include "cartesian3dgrid/gaussianiir3d.h"
7 |
8 |
9 | void Grid3D::smoothInPlaceIIR3D(const float sigma_x, const float sigma_y, const float sigma_z)
10 | {
11 | int numsteps = 3;
12 | gaussianiir3d(&(data_array_.at(0)), size_[0], size_[1], size_[2], sigma_x, sigma_y, sigma_z, numsteps);
13 | }
14 |
15 |
16 | /**
17 | * \brief Diffuse grid using the heat equation (isotropic Gaussian blur)
18 | */
19 | void diffuse ( std::vector* grid, const unsigned int width, const unsigned int height, const unsigned int depth,
20 | const float sigma)
21 | {
22 | std::vector grid_new(width*height*depth,0.f); // temporary array
23 |
24 | const float dt_CFL = 1.f / 12.f; // 3D heat equation, explicit scheme stability condition
25 | const float t_final = 0.5f * sigma*sigma;
26 | const float dt = std::min( 0.5f*dt_CFL, 0.5f*t_final);
27 | unsigned int steps = std::ceil(t_final / dt);
28 |
29 | const int stride_x = 1, stride_y = width, stride_z = width*height;
30 |
31 | while ( steps-- )
32 | {
33 | for (int iz=0, p=0; iz < depth; iz++)
34 | {
35 | for (int iy=0; iy < height; iy++)
36 | {
37 | for (int ix=0; ix < width; ix++, p++)
38 | {
39 | // Boundary conditions: homogeneous Neumann
40 | int dx_pos = stride_x; if (ix+1 >= width){dx_pos = 0;}
41 | int dx_neg = -stride_x; if (ix-1 < 0){dx_neg = 0;}
42 | int dy_pos = stride_y; if (iy+1 >= height){dy_pos = 0;}
43 | int dy_neg = -stride_y; if (iy-1 < 0){dy_neg = 0;}
44 | int dz_pos = stride_z; if (iz+1 >= depth){dz_pos = 0;}
45 | int dz_neg = -stride_z; if (iz-1 < 0){dz_neg = 0;}
46 |
47 | // Index of current point
48 | //int p = stride_x*ix + stride_y*iy + stride_z*iz;
49 | // Compute 3D Laplacian: sum of second order derivatives
50 | float grid_p = grid->at(p);
51 | float Dxx = grid->at(p+dx_pos) - 2*grid_p + grid->at(p+dx_neg);
52 | float Dyy = grid->at(p+dy_pos) - 2*grid_p + grid->at(p+dy_neg);
53 | float Dzz = grid->at(p+dz_pos) - 2*grid_p + grid->at(p+dz_neg);
54 | // Update current point with explicit Euler scheme.
55 | // Stability condition (CFL) is 1-6*dt > 0
56 | grid_new.at(p) = grid_p + dt * ( Dxx + Dyy + Dzz );
57 | }
58 | }
59 | }
60 | grid->swap(grid_new);
61 | }
62 | }
63 |
64 |
65 | //void Grid3D::smoothInPlace(const float sigma_x, const float sigma_y, const float sigma_z)
66 | void Grid3D::smoothInPlace(const float sigma)
67 | {
68 | diffuse ( &data_array_, size_[0], size_[1], size_[2], sigma);
69 | }
70 |
71 |
72 | void laplacian3D ( std::vector* grid, const unsigned int width, const unsigned int height, const unsigned int depth)
73 | {
74 | std::vector grid_new(width*height*depth,0.f); // temporary array
75 |
76 | const int stride_x = 1, stride_y = width, stride_z = width*height;
77 |
78 | for (int iz=0, p=0; iz < depth; iz++)
79 | {
80 | for (int iy=0; iy < height; iy++)
81 | {
82 | for (int ix=0; ix < width; ix++, p++)
83 | {
84 | // Boundary conditions: homogeneous Neumann
85 | int dx_pos = stride_x; if (ix+1 >= width){dx_pos = 0;}
86 | int dx_neg = -stride_x; if (ix-1 < 0){dx_neg = 0;}
87 | int dy_pos = stride_y; if (iy+1 >= height){dy_pos = 0;}
88 | int dy_neg = -stride_y; if (iy-1 < 0){dy_neg = 0;}
89 | int dz_pos = stride_z; if (iz+1 >= depth){dz_pos = 0;}
90 | int dz_neg = -stride_z; if (iz-1 < 0){dz_neg = 0;}
91 |
92 | // Index of current point
93 | //int p = stride_x*ix + stride_y*iy + stride_z*iz;
94 | // Compute 3D Laplacian: sum of second order derivatives
95 | float grid_p = grid->at(p);
96 | float Dxx = grid->at(p+dx_pos) - 2*grid_p + grid->at(p+dx_neg);
97 | float Dyy = grid->at(p+dy_pos) - 2*grid_p + grid->at(p+dy_neg);
98 | float Dzz = grid->at(p+dz_pos) - 2*grid_p + grid->at(p+dz_neg);
99 | grid_new.at(p) = Dxx + Dyy + Dzz;
100 | }
101 | }
102 | }
103 | grid->swap(grid_new);
104 | }
105 |
106 |
107 | void Grid3D::laplacianInPlace()
108 | {
109 | laplacian3D ( &data_array_, size_[0], size_[1], size_[2]);
110 | }
111 |
112 |
113 | double Grid3D::computeMoranIndexGaussianWeights(float sigma) const
114 | {
115 | if (sigma < 0.2)
116 | {
117 | // Need some "minimum" width to provide meaningful results
118 | sigma = 0.2;
119 | }
120 |
121 | // Standardized grid values
122 | double mean, stddev;
123 | computeMeanStd(&mean, &stddev);
124 | std::cout << "Grid3D: Mean = " << mean << " std = " << stddev << std::endl;
125 |
126 | float inv_stddev_f = 1.f / stddev;
127 | std::vector data_array_standardized(numCells_,0.f);
128 | for (int i=0; i data_array_standardized_smooth;
133 | data_array_standardized_smooth = data_array_standardized; // copy
134 | //diffuse(&data_array_standardized_smooth, size_[0], size_[1], size_[2], sigma);
135 | gaussianiir3d(&(data_array_standardized_smooth.at(0)), size_[0], size_[1], size_[2], sigma, sigma, sigma, 3);
136 |
137 | // Compute central weight of Gaussian kernel and its complement, the sum of weights of the neighbors
138 | const int half_size = 2 * std::ceil(3.f*sigma); // 2 to mitigate boundary issues
139 | const int kernel_size = 2*half_size + 1;
140 | std::vector weights(kernel_size*kernel_size*kernel_size, 0.f);
141 | unsigned int idx_center = half_size + kernel_size*(half_size + kernel_size*half_size);
142 | weights.at(idx_center) = 1.f;
143 | //diffuse(&weights, kernel_size, kernel_size, kernel_size, sigma);
144 | gaussianiir3d(&(weights.at(0)), kernel_size, kernel_size, kernel_size, sigma, sigma, sigma, 3);
145 |
146 | const float central_weight = weights.at(idx_center);
147 | /*
148 | //DEBUG
149 | std::cout << "sigma = " << sigma << std::endl;
150 | std::cout << "kernel_size = " << kernel_size << std::endl;
151 | std::cout << "central_weight = " << central_weight << std::endl;
152 | // print kernel
153 | std::cout << "weights" << std::endl;
154 | for (int iz=0; iz < kernel_size; iz++)
155 | {
156 | std::cout << "iz = " << iz << std::endl;
157 | for (int iy=0; iy < kernel_size; iy++)
158 | {
159 | for (int ix=0; ix < kernel_size; ix++)
160 | {
161 | int idx = ix + kernel_size*(iy + kernel_size*iz);
162 | std::cout << weights.at(idx) << " ";
163 | }
164 | std::cout << std::endl;
165 | }
166 | std::cout << std::endl;
167 | }
168 | */
169 |
170 | // Compute sum of the weights (of the neighbors)
171 | const float sum_weights = 1.f - central_weight;
172 | /*
173 | //DEBUG
174 | weights.at(idx_center) = 0.f; // "remove" central point
175 | float sum_weights2 = 0.f;
176 | const int numCells = kernel_size*kernel_size*kernel_size;
177 | for (int i=0; i 0; x--)
86 | ptr[x - 1] += nu*ptr[x];
87 | }
88 | }
89 | }
90 |
91 | /* Filter vertically along each column */
92 | for(z = 0; z < depth; z++)
93 | {
94 | for(x = 0; x < width; x++)
95 | {
96 | for(step = 0; step < numsteps; step++)
97 | {
98 | ptr = volume + x + plane*z;
99 | ptr[0] *= boundaryscale;
100 |
101 | /* Filter downwards */
102 | for(i = width; i < plane; i += width)
103 | ptr[i] += nu*ptr[i - width];
104 |
105 | ptr[i = plane - width] *= boundaryscale;
106 |
107 | /* Filter upwards */
108 | for(; i > 0; i -= width)
109 | ptr[i - width] += nu*ptr[i];
110 | }
111 | }
112 | }
113 |
114 | /* Filter along z-dimension */
115 | for(y = 0; y < height; y++)
116 | {
117 | for(x = 0; x < width; x++)
118 | {
119 | for(step = 0; step < numsteps; step++)
120 | {
121 | ptr = volume + x + width*y;
122 | ptr[0] *= boundaryscale;
123 |
124 | for(i = plane; i < numel; i += plane)
125 | ptr[i] += nu*ptr[i - plane];
126 |
127 | ptr[i = numel - plane] *= boundaryscale;
128 |
129 | for(; i > 0; i -= plane)
130 | ptr[i - plane] += nu*ptr[i];
131 | }
132 | }
133 | }
134 |
135 | for(i = 0; i < numel; i++)
136 | volume[i] *= postscale;
137 |
138 | return;
139 | }
140 |
141 |
142 | // Allow for a different sigma in each dimension
143 | void gaussianiir3d(float *volume, long width, long height, long depth, float sigma_x, float sigma_y, float sigma_z, int numsteps)
144 | {
145 | const long plane = width*height;
146 | const long numel = plane*depth;
147 | double lambda, dnu;
148 | float nu, boundaryscale, postscale = 1.f;
149 | float *ptr;
150 | long i, x, y, z;
151 | int step;
152 |
153 | if(sigma_x <= 0 || sigma_y <= 0 || sigma_z <= 0 || numsteps < 0)
154 | return;
155 |
156 | /* Filter horizontally along each row */
157 |
158 | lambda = (sigma_x*sigma_x)/(2.0*numsteps);
159 | dnu = (1.0 + 2.0*lambda - sqrt(1.0 + 4.0*lambda))/(2.0*lambda);
160 | nu = (float)dnu;
161 | boundaryscale = (float)(1.0/(1.0 - dnu));
162 | float postscale_x = (float)(pow(dnu/lambda,numsteps));
163 | postscale *= postscale_x;
164 |
165 | for(z = 0; z < depth; z++)
166 | {
167 | for(y = 0; y < height; y++)
168 | {
169 | for(step = 0; step < numsteps; step++)
170 | {
171 | ptr = volume + width*(y + height*z);
172 | ptr[0] *= boundaryscale;
173 |
174 | /* Filter rightwards */
175 | for(x = 1; x < width; x++)
176 | ptr[x] += nu*ptr[x - 1];
177 |
178 | ptr[x = width - 1] *= boundaryscale;
179 |
180 | /* Filter leftwards */
181 | for(; x > 0; x--)
182 | ptr[x - 1] += nu*ptr[x];
183 | }
184 | }
185 | }
186 |
187 | /* Filter vertically along each column */
188 |
189 | lambda = (sigma_y*sigma_y)/(2.0*numsteps);
190 | dnu = (1.0 + 2.0*lambda - sqrt(1.0 + 4.0*lambda))/(2.0*lambda);
191 | nu = (float)dnu;
192 | boundaryscale = (float)(1.0/(1.0 - dnu));
193 | float postscale_y = (float)(pow(dnu/lambda,numsteps));
194 | postscale *= postscale_y;
195 |
196 | for(z = 0; z < depth; z++)
197 | {
198 | for(x = 0; x < width; x++)
199 | {
200 | for(step = 0; step < numsteps; step++)
201 | {
202 | ptr = volume + x + plane*z;
203 | ptr[0] *= boundaryscale;
204 |
205 | /* Filter downwards */
206 | for(i = width; i < plane; i += width)
207 | ptr[i] += nu*ptr[i - width];
208 |
209 | ptr[i = plane - width] *= boundaryscale;
210 |
211 | /* Filter upwards */
212 | for(; i > 0; i -= width)
213 | ptr[i - width] += nu*ptr[i];
214 | }
215 | }
216 | }
217 |
218 | /* Filter along z-dimension */
219 |
220 | lambda = (sigma_z*sigma_z)/(2.0*numsteps);
221 | dnu = (1.0 + 2.0*lambda - sqrt(1.0 + 4.0*lambda))/(2.0*lambda);
222 | nu = (float)dnu;
223 | boundaryscale = (float)(1.0/(1.0 - dnu));
224 | float postscale_z = (float)(pow(dnu/lambda,numsteps));
225 | postscale *= postscale_z;
226 |
227 | for(y = 0; y < height; y++)
228 | {
229 | for(x = 0; x < width; x++)
230 | {
231 | for(step = 0; step < numsteps; step++)
232 | {
233 | ptr = volume + x + width*y;
234 | ptr[0] *= boundaryscale;
235 |
236 | for(i = plane; i < numel; i += plane)
237 | ptr[i] += nu*ptr[i - plane];
238 |
239 | ptr[i = numel - plane] *= boundaryscale;
240 |
241 | for(; i > 0; i -= plane)
242 | ptr[i - plane] += nu*ptr[i];
243 | }
244 | }
245 | }
246 |
247 | for(i = 0; i < numel; i++)
248 | volume[i] *= postscale;
249 |
250 | return;
251 | }
252 |
--------------------------------------------------------------------------------
/data/DSEC/interlaken_00-odometry/pose.bag:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/data/DSEC/interlaken_00-odometry/pose.bag
--------------------------------------------------------------------------------
/data/DSEC/zurich_city_02-odometry/pose.bag:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/data/DSEC/zurich_city_02-odometry/pose.bag
--------------------------------------------------------------------------------
/data/DSEC/zurich_city_04-odometry/pose.bag:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/data/DSEC/zurich_city_04-odometry/pose.bag
--------------------------------------------------------------------------------
/dependencies.yaml:
--------------------------------------------------------------------------------
1 | repositories:
2 | catkin_simple:
3 | type: git
4 | url: https://github.com/catkin/catkin_simple.git
5 | version: master
6 | rpg_dvs_ros:
7 | type: git
8 | url: https://github.com/uzh-rpg/rpg_dvs_ros.git
9 | version: master
10 | gflags_catkin:
11 | type: git
12 | url: https://github.com/ethz-asl/gflags_catkin.git
13 | version: master
14 | glog_catkin:
15 | type: git
16 | url: https://github.com/ethz-asl/glog_catkin.git
17 | version: master
18 | minkindr:
19 | type: git
20 | url: https://github.com/ethz-asl/minkindr.git
21 | version: master
22 | eigen_catkin:
23 | type: git
24 | url: https://github.com/ethz-asl/eigen_catkin.git
25 | version: master
26 | eigen_checks:
27 | type: git
28 | url: https://github.com/ethz-asl/eigen_checks.git
29 | version: master
30 | cnpy:
31 | type: git
32 | url: git@github.com:uzh-rpg/cnpy_catkin.git
33 | version: master
34 | vicon:
35 | type: git
36 | url: https://github.com/KumarRobotics/vicon
37 | version: master
38 |
39 |
--------------------------------------------------------------------------------
/docs/2022_MCEVMS_poster.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/docs/2022_MCEVMS_poster.pdf
--------------------------------------------------------------------------------
/docs/block_all.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/docs/block_all.png
--------------------------------------------------------------------------------
/docs/datasets.md:
--------------------------------------------------------------------------------
1 | ### Datasets
2 | - HKUST and edited RPG-ECCV 18 datasets [ESVO 2020](https://sites.google.com/view/esvo-project-page/home#h.tl1va3u667ae)
3 | - [RPG-ECCV 2018](http://rpg.ifi.uzh.ch/ECCV18_stereo_davis.html)
4 | - [MVSEC, RAL 2018](https://daniilidis-group.github.io/mvsec/)
5 | - [DSEC](https://dsec.ifi.uzh.ch/). Additionally, camera poses for some sequences are provided [in this directory](../data/DSEC).
6 | - [TUM-VIE](https://vision.in.tum.de/data/datasets/visual-inertial-event-dataset)
7 |
8 | Our code expects ROSBags for input events and poses. To convert event data from HDF5 files (as in DSEC, TUM-VIE) to ROSBags quickly, you may use [our events_h52bag C++ utility](https://github.com/tub-rip/events_h52bag).
9 |
10 | We suggest pre-processing the event data using the [DVS hot pixel filter](https://github.com/cedric-scheerlinck/dvs_tools/tree/master/dvs_hot_pixel_filter). It outputs bag files with a `.filtered` extension.
11 |
--------------------------------------------------------------------------------
/docs/evaluation.md:
--------------------------------------------------------------------------------
1 | ### Evaluation scripts
2 | * **Visualization of the Disparity Space Images (DSIs)** can be done using the python scripts provided [here](https://github.com/tub-rip/dvs_mcemvs/blob/main/mapper_emvs_stereo/scripts). Please refer to the [the monocular package](https://github.com/uzh-rpg/rpg_emvs/blob/master/README.md#disparity-space-image-dsi) for documentation about using them.
3 | * We provide [an example script](https://github.com/tub-rip/dvs_mcemvs/blob/main/mapper_emvs_stereo/scripts/evaluate_mcemvs_dsec.py) for **computing the depth error metrics** for DSEC. Please modify the data paths before running.
4 |
--------------------------------------------------------------------------------
/docs/examples.md:
--------------------------------------------------------------------------------
1 | ## Running Examples
2 | ### DSEC
3 |
4 | From the [DSEC dataset](https://dsec.ifi.uzh.ch/dsec-datasets/download/), download the following files:
5 | * [interlaken_00_b_events_left.zip](https://download.ifi.uzh.ch/rpg/DSEC/test/interlaken_00_b/interlaken_00_b_events_left.zip)
6 | * [interlaken_00_b_events_right.zip](https://download.ifi.uzh.ch/rpg/DSEC/test/interlaken_00_b/interlaken_00_b_events_right.zip)
7 | * [interlaken_00_b_calibration.zip](https://download.ifi.uzh.ch/rpg/DSEC/test/interlaken_00_b/interlaken_00_b_calibration.zip) for camera and hand-eye calibration.
8 |
9 | Camera poses obtained using LiDAR-IMU odometry are available [here](../data/DSEC/interlaken_00-odometry/pose.bag) in ROSBag format. Thanks to [Mathias Gehrig](https://magehrig.github.io/) for the data.
10 |
11 | Extract the zip files. Convert left and right events from h5 format to ROSBag.
12 | Clone and install [our h52bag converter](https://github.com/tub-rip/events_h52bag). Then, convert using:
13 |
14 | ./events_h52bag interlaken_00_b_events_left/events.h5 interlaken_00_b_events_left /dvs/left/events 480 640
15 | ./events_h52bag interlaken_00_b_events_right/events.h5 interlaken_00_b_events_right /dvs/right/events 480 640
16 |
17 | Since each h5 file is big (>500M events), this will generate multiple ROSBag files containing events from both cameras. In this example, we'll use the files `interlaken_00_b_events_left_1.bag` and `interlaken_00_b_events_right_1.bag`, which comprises a subset of the whole `interlaken_00_b` sequence.
18 |
19 | Set the correct path of the input events, poses and the unzipped calibration files by editing the configuration file `mapper_emvs_stereo/cfg/DSEC/interlaken_00_b_2/dsec.conf`.
20 |
21 | Finally, run mapper_emvs_stereo:
22 |
23 | roscd mapper_emvs_stereo
24 | cd cfg/DSEC/interlaken_00_b_2
25 | rosrun mapper_emvs_stereo run_emvs --flagfile=dsec.conf
26 |
27 | This will process the subsequence `interlaken_00_b_1` and generate a sequence of time-stamped output files (depth maps and confidence maps) in the current folder.
28 |
29 |
30 |
31 |  |
32 |  |
33 |
34 |
35 | Depth map |
36 | Confidence map |
37 |
38 |
39 |
40 | ### RPG_ECCV18_edited
41 |
42 | Download the [rpg_monitor_edited.bag](https://drive.google.com/file/d/1P8N3YfYnF5lgOgZGqkMU73otEnedztgy/view?usp=drive_web) file from the [ESVO 2020](https://sites.google.com/view/esvo-project-page/home#h.tl1va3u667ae), which contains stereo events and camera poses.
43 |
44 | Set the correct path of the filtered bag file in the `--bag_filename` parameter in the file `mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/alg1/rpg_monitor_edited_fixedts.conf`. Make sure that the topic names are correct. Finally, run mapper_emvs_stereo
45 |
46 | roscd mapper_emvs_stereo
47 | cd cfg/rpg_eccv18/monitor_edited/alg1/
48 | rosrun mapper_emvs_stereo run_emvs --flagfile=rpg_monitor_edited_fixedts.conf
49 |
50 | The output files will be saved in the current directory.
51 | The raw depth points are stored in `014.000000depth_points_fused_2.txt`file in the format `[row column depth]`.
52 | The color-coded inverse depth map is saved as `014.000000inv_depth_colored_dilated_fused_2.png`.
53 | The suffix `_2` denotes the fusion function used (Harmonic mean -HM- in this case).
54 |
55 |
56 |
57 |  |
58 |  |
59 |
60 |
61 | Depth map |
62 | Confidence map |
63 |
64 |
65 |
66 |
67 | ### TUM-VIE
68 |
69 | From the [TUM-VIE dataset](https://vision.in.tum.de/data/datasets/visual-inertial-event-dataset), download the following files:
70 | * [mocap-desk2-events_left.h5](https://tumevent-vi.vision.in.tum.de/mocap-desk2/mocap-desk2-events_left.h5)
71 | * [mocap-desk2-events_right.h5](https://tumevent-vi.vision.in.tum.de/mocap-desk2/mocap-desk2-events_right.h5)
72 | * [mocap-desk2-vi_gt_data.tar.gz](https://tumevent-vi.vision.in.tum.de/mocap-desk2/mocap-desk2-vi_gt_data.tar.gz) for camera poses.
73 | * [camera-calibrationA.json](https://tumevent-vi.vision.in.tum.de/camera-calibrationA.json) for camera and hand-eye calibration.
74 |
75 |
76 | Convert left and right events from h5 format to ROSBag.
77 | Clone and install [our h52bag converter](https://github.com/tub-rip/events_h52bag). Then, convert using:
78 |
79 | ./events_h52bag mocap-desk2-events_left.h5 mocap-desk2-events_left /dvs/left/events 720 1280 700000000
80 | ./events_h52bag mocap-desk2-events_right.h5 mocap-desk2-events_right /dvs/left/events 720 1280 700000000
81 |
82 | This should generate 2 bag files for the events, namely `mocap-desk2-events_left_0.bag` and `mocap-desk2-events_right_0.bag`. This was tested with 32GB RAM. If you run out of memory, use a lower number for `events_per_bag` instead `700000000`. This will split the output into multiple ROSBag files.
83 |
84 | Extract the contents of `mocap-desk2-vi_gt_data.tar.gz` into a folder `mocap-desk2-vi_gt_data`. Then, convert poses from `mocap_data.txt` to ROSBag using [this script](../mapper_emvs_stereo/scripts/mocap_txt2bag.py):
85 |
86 | python mapper_emvs_stereo/scripts/mocap_txt2bag.py --path_prefix mocap-desk2-vi_gt_data
87 |
88 | This should generate `pose.bag` as output inside the `mocap-desk2-vi_gt_data` folder.
89 |
90 | Set the correct path of the input events, poses and the calibration file by editing the configuration file `mapper_emvs_stereo/cfg/tumvie/desk2_full/tum-vie.conf`.
91 |
92 | Finally, run mapper_emvs_stereo:
93 |
94 | roscd mapper_emvs_stereo
95 | cd cfg/rpg_eccv18/tumvie/desk2_full
96 | rosrun mapper_emvs_stereo run_emvs --flagfile=tum-vie.conf
97 |
98 | This will process the whole desk2 sequence and generate a sequence of time-stamped output files (depth maps and confidence maps) in the current folder.
99 |
100 |
101 |
102 |  |
103 |  |
104 |
105 |
106 | Depth map |
107 | Confidence map |
108 |
109 |
110 |
--------------------------------------------------------------------------------
/docs/installation.md:
--------------------------------------------------------------------------------
1 | ## Dependencies
2 |
3 | ### Install ROS Noetic (Ubuntu 20.04)
4 |
5 | ### Create a catkin workspace
6 |
7 | Create a catkin workspace (if there is none yet). For example, from your home folder:
8 |
9 | cd
10 | mkdir -p catkin_ws/src
11 | cd catkin_ws
12 | catkin config --init --mkdirs --extend /opt/ros/noetic --merge-devel --cmake-args -DCMAKE_BUILD_TYPE=Release
13 |
14 | The code has been tested on ROS Noetic. Depending on the ROS distribution you installed, you might have to use `kinetic` or `melodic` instead of `noetic` in the previous command.
15 |
16 | ### Add packages to the catkin workspace
17 |
18 | **Clone** this repository into the `src` folder of your catkin workspace.
19 |
20 | cd catkin_ws/src
21 | git clone git@github.com:tub-rip/dvs_mcemvs.git
22 |
23 | The catkin package dependencies are:
24 | - [catkin simple](https://github.com/catkin/catkin_simple)
25 | - ROS messages for DVS ([rpg_dvs_ros](https://github.com/uzh-rpg/rpg_dvs_ros))
26 | - [Google Logging Library (glog)](https://github.com/catkin/catkin_simple.git)
27 | - [Gflags (formerly Google Commandline Flags)](https://github.com/ethz-asl/gflags_catkin)
28 | - [minkindr](https://github.com/ethz-asl/minkindr) (for dealing with poses). minkindr depends on [eigen_catkin](https://github.com/ethz-asl/eigen_catkin.git) and [eigen_checks](https://github.com/ethz-asl/eigen_checks.git), which are therefore also required.
29 | - [vicon](https://github.com/KumarRobotics/vicon) for reading poses in the form of vicon_msg
30 |
31 | The above dependencies are specified in the [dependencies.yaml](dependencies.yaml) file. They can be installed with the following commands from the `src` folder of your catkin workspace:
32 |
33 | cd catkin_ws/src
34 | sudo apt-get install python3-vcstool
35 | vcs-import < dvs_mcemvs/dependencies.yaml
36 |
37 | The previous command should clone the repositories into folders *catkin_simple*, *rpg_dvs_ros*, etc. inside the src/ folder of your catkin workspace, at the same level as this repository *dvs_mcemvs*. They should NOT be inside the *dvs_mcemvs* folder.
38 |
39 | Additional ROS tools needed (specified in the [package.xml](package.xml) file):
40 |
41 | sudo apt-get install ros-noetic-image-geometry
42 | sudo apt-get install ros-noetic-tf-conversions
43 |
44 | ## Compiling
45 |
46 | **Compile this package**:
47 |
48 | catkin build mapper_emvs_stereo
49 |
50 | After building, at least the first time, remember to run:
51 |
52 | source ~/catkin_ws/devel/setup.bash
53 |
54 | Sometimes (in case of strange errors) it is useful to delete the build folder before compilation:
55 |
56 | rm -rf build/mapper_emvs_stereo/
57 |
58 | An alternative command to start from scratch (cleaning all catkin packages) is (to be used with *caution*): `catkin clean`
59 |
--------------------------------------------------------------------------------
/docs/mcemvs_thumbnail.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/tub-rip/dvs_mcemvs/9ae7a374c72f2653c42cd36d663698eee8cfe509/docs/mcemvs_thumbnail.jpg
--------------------------------------------------------------------------------
/docs/running.md:
--------------------------------------------------------------------------------
1 | ## Running the code
2 |
3 | Running the code:
4 |
5 | rosrun mapper_emvs_stereo run_emvs --flagfile=
6 |
7 | The `` is used to define the set of parameters passed on the program. Examples of configuration files are provided in the `mapper_emvs_stereo/cfg` folder for different datasets and variants of the algorithm.
8 |
9 | ### Variants
10 |
11 | * **alg1**: Algorithm 1 in the paper. Only stereo fusion across cameras. This is the default variant if nothing is specified in the folder name.
12 | * **fusionfuncs**: Configurations for using different fusion functions for across-camera fusion -- minimum (min), Harmonic Mean (HM), Geometric Mean (GM), Arithmetic Mean (AM), Root Mean Square (RMS), maximum (max).
13 | * **alg2**: Algorithm 2 in the paper. Includes both temporal and stereo camera fusion. Different combinations of Arithmetic Mean (A) and Harmonic Mean (H) can be applied for temporal (t) and camera (c) fusion. For example, `AtHc` implies across-camera fusion happens first using Harmonic Mean, followed by temporal fusion using Arithmetic Mean. The order is important.
14 | * **shuffled**: Special case of algorithm 2, where the event sub-intervals of the stereo pair are shuffled before fusion. Denoted by `_shuffled` in the folder name suffix.
15 | * **full**: When a long data stream is broken into chunks and processed independently to produce a sequence of depth maps. Denoted by `_full` in the folder name.
16 |
17 | ### Configuration Parameters
18 |
19 | The main parameters of the `.conf` files are described below. Please take a look at `mapper_emvs_stereo/src/main.cpp` for a comprehensive list.
20 |
21 | * **bag_filename**: Path to single ROSBag file containing all events and camera poses. Otherwise, use the next 3 parameters when the data is available is separate bag files.
22 | * **bag_filename_left**: Path to ROSbag file containing left camera events
23 | * **bag_filename_right**: Path to ROSbag file containing right camera events
24 | * **bag_filename_pose**: Path to ROSbag file containing pose of stereo rig
25 | * **out_path**: Path to output results
26 | * **calib_type**: Refers to how calibration data has been provided (YAML, JSON, hard-coded etc.), depending on the source of the dataset. Refer to the `.conf` files to find the correct value of this parameter for each dataset.
27 | * **calib_path**: Path to intrinsic and extrinsic camera calibration file, needed for certain datasets specified by `calib_type`.
28 | * **mocap_calib_path**: Path to hand-eye calibration file, needed for certain datasets specified by `calib_type`.
29 | * **event_topic0**: Left event camera topic
30 | * **event_topic1**: Right event camera topic
31 | * **event_topic2** : Third event camera topic for trinocular fusion
32 | * **pose_topic**: Topic containing the pose of the stereo rig
33 | * **min_depth**: Minimum estimable depth of the scene
34 | * **max_depth**: Maximum estimable depth of the scene
35 | * **start_time_s**: Time (in seconds) from which we start processing events
36 | * **stop_time_s**: Time (in seconds) till which events are processed
37 | * **dimZ**: Number of depth planes to place within the assumed scene depth range. By default, the planes are uniformly distributed in _inverse depth_ space. To place depth planes uniformly along _depth_ space, turn the setting `DEFINE_USE_INVERSE_DEPTH` in `mapper_emvs_stereo/CMakeLists.txt` to `OFF`.
38 | * **process_method**: 1, 2 or 5.
39 | - 1: Algorithm 1 (fusion only across cameras);
40 | - 2: Algorithm 2 (fusion across cameras and time);
41 | - 5: Algorithm 2 + shuffling (shuffle sub-intervals before fusion)
42 | * **stereo_fusion**: A number between 1-6. It decides the method used to fuse DSIs across cameras.
43 | - 1: min;
44 | - 2: Harmonic mean;
45 | - 3: Geometric mean;
46 | - 4: Arithmetic mean;
47 | - 5: RMS mean;
48 | - 6: max
49 | * **temporal_fusion**: This parameter is used only when `process_method=2`. It describes the method used to fuse DSIs in time. Currently, only 2 (Harmonic mean) and 4 (Arithmetic mean) are supported.
50 | * **num_intervals**: This parameter is used only when `process_method=2`. Algorithm 2 divides the entire data duration into this many sub-intervals of equal duration.
51 | * **ts**: Timestamp (in seconds) of the left camera trajectory at which the reference view of the DSI is set. By default, it is set at mid-point of start and stop times.
52 | * **adaptive_threshold_c**: Parameter for Gaussian adaptive thresholding filter applied on the DSI before extracting depth map
53 | * **median_filter_size**: Kernel size of median filter applied on DSI for removing noise
54 | * **full_seq**: Divide a data sequence into smaller sections in time and process each chunk independently. A sliding window of a certain duration and stride is used to process the whole input sequence. This is used for generating sequences of depth maps over long sequences of data.
55 | * **duration**: Used only when `full_seq=true`. It specifies the duration (in seconds) each chunk of data that is processed independently.
56 | * **out_skip**: Used only when `full_seq=true`. It desribes the stride (in seconds) of the sliding window used to process the entire input sequence. The output depth frame rate is modulated with this parameter.
57 | * **max_confidence**: Use this value to manually set the upper limit of the range of values in each DSI, before normalization to [0, 255]. If set to 0 (by default), the maximum value of each DSI is used as its upper limit. For long sequences, setting a constant upper limit for all DSIs regularizes depth map filtering, and prevents sections with low event count from generating noisy depth estimates. In conjunction with `adaptive_threshold_c`, this values regulates the trade-off between reconstructing more 3D points and filtering out noise. Icreasing this parameter makes noise filtering stricter.
58 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | project(mapper_emvs_stereo)
2 | set(CMAKE_CXX_STANDARD 14)
3 | set(CMAKE_CXX_STANDARD_REQUIRED ON)
4 | cmake_minimum_required(VERSION 2.8.3)
5 |
6 | find_package(catkin_simple REQUIRED COMPONENTS
7 | tf
8 | tf_conversions
9 | eigen_conversions
10 | vicon)
11 | catkin_simple(ALL_DEPS_REQUIRED)
12 |
13 | set(CMAKE_BUILD_TYPE RelWithDebInfo) # Release, RelWithDebInfo
14 | set(CMAKE_CXX_FLAGS "-O3 -fopenmp ${CMAKE_CXX_FLAGS}")
15 |
16 | set(HEADERS
17 | include/mapper_emvs_stereo/mapper_emvs_stereo.hpp
18 | include/mapper_emvs_stereo/data_loading.hpp
19 | include/mapper_emvs_stereo/depth_vector.hpp
20 | include/mapper_emvs_stereo/trajectory.hpp
21 | include/mapper_emvs_stereo/geometry_utils.hpp
22 | include/mapper_emvs_stereo/median_filtering.hpp
23 | include/mapper_emvs_stereo/calib.hpp
24 | include/mapper_emvs_stereo/utils.hpp
25 | include/mapper_emvs_stereo/process1.hpp
26 | include/mapper_emvs_stereo/process2.hpp
27 | include/mapper_emvs_stereo/process5.hpp
28 | )
29 |
30 | set(SOURCES
31 | src/mapper_emvs_stereo.cpp
32 | src/data_loading.cpp
33 | src/median_filtering.cpp
34 | src/calib.cpp
35 | src/utils.cpp
36 | src/process1.cpp
37 | src/process2.cpp
38 | src/process5.cpp
39 | )
40 |
41 | option(DEFINE_USE_INVERSE_DEPTH "Use linear spacing in inverse depth (if OFF, will use linear spacing in depth)" OFF)
42 | if(DEFINE_USE_INVERSE_DEPTH)
43 | add_definitions(-DUSE_INVERSE_DEPTH)
44 | endif(DEFINE_USE_INVERSE_DEPTH)
45 |
46 | cs_add_library(${PROJECT_NAME} ${SOURCES} ${HEADERS})
47 |
48 | # Executables
49 | ################################################################################
50 |
51 | cs_add_executable(run_emvs src/main.cpp)
52 | target_link_libraries(run_emvs ${PROJECT_NAME} yaml-cpp)
53 |
54 | ################################################################################
55 | cs_install()
56 | cs_export()
57 |
58 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/DSEC/interlaken_00_b_2/dsec.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/home/suman/data/rpg/DSEC/interlaken_00_b/interlaken_00_b_events_left_2.bag
2 | --bag_filename_right=/home/suman/data/rpg/DSEC/interlaken_00_b/interlaken_00_b_events_right_2.bag
3 | --bag_filename_pose=/home/suman/data/rpg/DSEC/interlaken_00-odometry/pose.bag
4 | --out_path=
5 | --calib_type=dsec_yaml
6 | --calib_path=/home/suman/data/rpg/DSEC/interlaken_00_b/interlaken_00_b_calibration/cam_to_cam.yaml
7 | --mocap_calib_path=/home/suman/data/rpg/DSEC/interlaken_00_b/interlaken_00_b_calibration/cam_to_lidar.yaml
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=4
12 | --max_depth=200
13 | --start_time_s=10
14 | --stop_time_s=35
15 | --duration=0.2
16 | --out_skip=1
17 | --dimZ=100
18 | --process_method=1
19 | --stereo_fusion=2
20 | --adaptive_threshold_c=4
21 | --max_confidence=0
22 | --forward_looking=true
23 | --full_seq=true
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/DSEC/zurich_04_a_full/dsec.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/home/suman/data/rpg/DSEC/zurich_city_04_a/left_events.bag
2 | --bag_filename_right=/home/suman/data/rpg/DSEC/zurich_city_04_a/right_events.bag
3 | --bag_filename_pose=/home/suman/data/rpg/DSEC/zurich_city_04-odometry/pose.bag
4 | --out_path=
5 | --calib_type=dsec_yaml
6 | --calib_path=/home/suman/data/rpg/DSEC/zurich_city_04_a/zurich_city_04_a_calibration/cam_to_cam.yaml
7 | --mocap_calib_path=/home/suman/data/rpg/DSEC/zurich_city_04_a/zurich_city_04_a_calibration/cam_to_lidar.yaml
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=4
12 | --max_depth=200
13 | --start_time_s=10
14 | --stop_time_s=15
15 | --duration=0.2
16 | --out_skip=0.1
17 | --dimZ=100
18 | --process_method=1
19 | --stereo_fusion=2
20 | --adaptive_threshold_c=4
21 | --max_confidence=468
22 | --forward_looking=true
23 | --full_seq=true
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/evimo2/evimo2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/evimo2/raw_sfm/sfm/eval/scene_03_00/scene_03_00.bag.filtered
2 | --out_path=
3 | --calib_path=
4 | --calib_type=evimo2
5 | --event_topic0=/samsung/camera/events
6 | --offset0=0.001
7 | --event_topic1=/prophesee/left/cd_events_buffer
8 | --offset1=-0.042
9 | --event_topic2=/prophesee/right/cd_events_buffer
10 | --offset2=-0.027
11 | --pose_topic=/vicon/dvs_rig
12 | --min_depth=0.5
13 | --max_depth=4
14 | --start_time_s=20.5
15 | --stop_time_s=21.5
16 | --ts=21
17 | --dimZ=100
18 | --process_method=1
19 | --stereo_fusion=2
20 | --adaptive_threshold_c=10
21 | --median_filter_size=9
22 | --save_mono=true
23 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/hkust/hkust_lab.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/suman/data/hkust/hkust_combined_filtered_hot.bag
2 | --out_path=
3 | --calib_path=
4 | --calib_type=hkust
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/esvo_tracking/pose_filtered
8 | --min_depth=0.5
9 | --max_depth=4
10 | --start_time_s=31.5
11 | --stop_time_s=32.5
12 | --ts=32
13 | --dimZ=100
14 | --process_method=1
15 | --stereo_fusion=2
16 | --adaptive_threshold_c=8
17 | --median_filter_size=7
18 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/AtHc/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=2
15 | --stereo_fusion=2
16 | --temporal_fusion=4
17 | --num_intervals=2
18 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/AtHc_shuffled/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/suman/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=5
15 | --stereo_fusion=2
16 | --temporal_fusion=4
17 | --num_intervals=2
18 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/alg1/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/suman/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=2
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_AM/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=4
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_GM/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=3
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_HM/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=2
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_RMS/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=5
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_max/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=6
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/boxes_edited/fusionfuncs/alg1_min/rpg_boxes_edited.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_boxes_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=0
10 | --stop_time_s=0.5
11 | --ts=0.25
12 | --dimZ=100
13 | --adaptive_threshold_c=5
14 | --process_method=1
15 | --stereo_fusion=1
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/AtHc/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=2
15 | --stereo_fusion=2
16 | --temporal_fusion=1
17 | --num_intervals=2
18 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/AtHc_shuffled/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/suman/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=5
15 | --stereo_fusion=2
16 | --temporal_fusion=4
17 | --num_intervals=2
18 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/alg1/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/rpg/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=2
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_AM/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=4
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_GM/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=3
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_HM/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=2
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_RMS/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=5
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_max/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=6
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/monitor_edited/fusionfuncs/alg1_min/rpg_monitor_edited_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/user/data/rpg_edited/rpg_monitor_edited.bag
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis/left/events
5 | --event_topic1=/davis/right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=13.5
10 | --stop_time_s=14.5
11 | --dimZ=100
12 | --ts=14
13 | --median_filter_size=5
14 | --process_method=1
15 | --stereo_fusion=1
16 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/rpg_eccv18/reader/alg1/rpg_reader_fixedts.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/home/suman/data/rpg/reader.bag.filtered
2 | --out_path=
3 | --calib_type=eccv18
4 | --event_topic0=/davis_left/events
5 | --event_topic1=/davis_right/events
6 | --pose_topic=/optitrack/davis_stereo
7 | --min_depth=0.55
8 | --max_depth=6.25
9 | --start_time_s=4.8
10 | --stop_time_s=5.6
11 | --dimZ=100
12 | --ts=5.2
13 | --process_method=1
14 | --stereo_fusion=2
15 | --adaptive_threshold_c=10
16 | --median_filter_size=7
17 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/bike-easy-3_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/bike-easy-events_left_3.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/bike-easy-events_right_3.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/bike-easy-vi_gt_data/basalt_pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=3
12 | --max_depth=100
13 | --start_time_s=1
14 | --stop_time_s=15
15 | --dimZ=100
16 | --process_method=1
17 | --out_skip=0.5
18 | --duration=0.5
19 | --adaptive_threshold_c=5
20 | --forward_looking=true
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/bike-easy-4_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/bike-easy-events_left_4.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/bike-easy-events_right_4.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/bike-easy-vi_gt_data/basalt_pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=3
12 | --max_depth=100
13 | --start_time_s=1
14 | --stop_time_s=20
15 | --dimZ=100
16 | --process_method=1
17 | --out_skip=0.5
18 | --duration=0.5
19 | --adaptive_threshold_c=5
20 | --forward_looking=true
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/bike-easy-5_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/bike-easy-events_left_5.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/bike-easy-events_right_5.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/bike-easy-vi_gt_data/basalt_pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=3
12 | --max_depth=100
13 | --start_time_s=1
14 | --stop_time_s=15
15 | --dimZ=100
16 | --process_method=1
17 | --out_skip=0.1
18 | --duration=0.5
19 | --adaptive_threshold_c=5
20 | --forward_looking=true
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/desk2_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/mocap-desk2-events_left.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/mocap-desk2-events_right.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/mocap-desk2-vi_gt_data/pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationA.json
7 | --mocap_calib_path=/mnt/HD4TB/data/tum-vie/mocap-imu-calibrationA.json
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=0.45
12 | --max_depth=4
13 | --start_time_s=10
14 | --stop_time_s=22
15 | --dimZ=100
16 | --process_method=1
17 | --adaptive_threshold_c=7
18 | --out_skip=0.5
19 | --duration=0.5
20 | --full_seq=true
21 | --max_confidence=0
22 | --save_conf_stats=true
23 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/mocap-1d-trans_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/mocap-1d-trans-events_left.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/mocap-1d-trans-events_right.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/mocap-1d-trans-vi_gt_data/pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=/mnt/HD4TB/data/tum-vie/mocap-imu-calibrationB.json
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=0.45
12 | --max_depth=4
13 | --start_time_s=5
14 | --stop_time_s=30
15 | --out_skip=1
16 | --duration=0.1
17 | --dimZ=100
18 | --process_method=1
19 | --adaptive_threshold_c=7
20 | --forward_looking=false
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/mocap-3d-trans_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/mocap-3d-trans-events_left.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/mocap-3d-trans-events_right.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/mocap-3d-trans-vi_gt_data/pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=/mnt/HD4TB/data/tum-vie/mocap-imu-calibrationB.json
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=0.45
12 | --max_depth=4
13 | --start_time_s=5
14 | --stop_time_s=30
15 | --out_skip=1
16 | --duration=0.1
17 | --dimZ=100
18 | --process_method=1
19 | --adaptive_threshold_c=7
20 | --forward_looking=false
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/running-easy-0_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/running-easy-events_left_0.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/running-easy-events_right_0.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/running-easy-vi_gt_data/pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=/mnt/HD4TB/data/tum-vie/mocap-imu-calibrationB.json
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=1
12 | --max_depth=20
13 | --start_time_s=9
14 | --stop_time_s=22
15 | --ts=6
16 | --dimZ=100
17 | --process_method=1
18 | --adaptive_threshold_c=7
19 | --duration=0.5
20 | --out_skip=0.5
21 | --forward_looking=false
22 | --full_seq=true
23 | --save_conf_stats=true
24 | --max_confidence=0
25 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/running-easy-1_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/running-easy-events_left_1.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/running-easy-events_right_1.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/running-easy-vi_gt_data/basalt_pose.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationB.json
7 | --mocap_calib_path=
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/pose
11 | --min_depth=1
12 | --max_depth=20
13 | --start_time_s=1
14 | --stop_time_s=20
15 | --dimZ=100
16 | --process_method=1
17 | --out_skip=0.1
18 | --duration=0.5
19 | --adaptive_threshold_c=5
20 | --forward_looking=true
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/tumvie/skate-easy-1_full/tum-vie.conf:
--------------------------------------------------------------------------------
1 | --bag_filename_left=/mnt/HD4TB/data/tum-vie/skate-easy-events_left_1.bag.filtered
2 | --bag_filename_right=/mnt/HD4TB/data/tum-vie/skate-easy-events_right_1.bag.filtered
3 | --bag_filename_pose=/mnt/HD4TB/data/tum-vie/skate-easy-vi_gt_data/odometry.bag
4 | --out_path=
5 | --calib_type=json
6 | --calib_path=/mnt/HD4TB/data/tum-vie/camera-calibrationA.json
7 | --mocap_calib_path=
8 | --event_topic0=/dvs/left/events
9 | --event_topic1=/dvs/right/events
10 | --pose_topic=/rovio/pose_with_covariance_stamped
11 | --min_depth=1
12 | --max_depth=20
13 | --start_time_s=1
14 | --stop_time_s=20
15 | --dimZ=100
16 | --process_method=1
17 | --out_skip=0.1
18 | --duration=0.5
19 | --adaptive_threshold_c=5
20 | --forward_looking=true
21 | --full_seq=true
22 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/AcAt/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=28.4
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/AcHt/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=28.1
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/AtHc/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=28.3
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/AtHc_shuffled/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=5
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=28.3
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/HcHt/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=28.1
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying1_full/alg1/flying1.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying1_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=65
12 | --dimZ=100
13 | --process_method=1
14 | --full_seq=true
15 | --out_skip=0.05
16 | --duration=1
17 | --adaptive_threshold_c=14
18 | --median_filter_size=9
19 | --max_confidence=57.7
20 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/AcAt/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=30.4
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/AcHt/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=29.4
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/AtHc/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=30.1
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/AtHc_shuffled/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=5
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=30.1
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/HcHt/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=29.3
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying2_full/norm_max_c14/flying2.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying2_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=79
12 | --dimZ=100
13 | --process_method=1
14 | --full_seq=true
15 | --out_skip=0.05
16 | --duration=1
17 | --adaptive_threshold_c=14
18 | --median_filter_size=9
19 | --max_confidence=78
20 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/AcAt/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=33.6
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/AcHt/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=4
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=30.6
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/AtHc/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=33.4
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/AtHc_shuffled/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=5
14 | --stereo_fusion=2
15 | --temporal_fusion=4
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=33.4
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/HcHt/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=2
14 | --stereo_fusion=2
15 | --temporal_fusion=2
16 | --num_intervals=2
17 | --out_skip=0.05
18 | --duration=1
19 | --adaptive_threshold_c=14
20 | --median_filter_size=9
21 | --full_seq=true
22 | --save_conf_stats=false
23 | --max_confidence=30.3
24 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/cfg/upenn_mvsec/mvsec_flying3_full/norm_max_c14/flying3.conf:
--------------------------------------------------------------------------------
1 | --bag_filename=/mnt/HD4TB/data/mvsec/indoor_flying3_combined.bag.filtered
2 | --out_path=
3 | --calib_type=yaml_mvsec
4 | --calib_path=/mnt/HD4TB/data/mvsec/calib_in_flying/camchain-imucam-indoor_flying.yaml
5 | --event_topic0=/davis/left/events
6 | --event_topic1=/davis/right/events
7 | --pose_topic=/davis/left/pose
8 | --min_depth=1
9 | --max_depth=6.5
10 | --start_time_s=10
11 | --stop_time_s=89
12 | --dimZ=100
13 | --process_method=1
14 | --full_seq=true
15 | --out_skip=0.05
16 | --duration=1
17 | --adaptive_threshold_c=14
18 | --median_filter_size=9
19 | --max_confidence=78.8
20 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/include/mapper_emvs_stereo/calib.hpp:
--------------------------------------------------------------------------------
1 | /*
2 | * \file calib.hpp
3 | * \brief header for calibration functions
4 | * \author (1) Suman Ghosh
5 | * \date 2022-09-01
6 | * \author (2) Guillermo Gallego
7 | * \date 2022-09-01
8 | * Copyright/Rights of Use:
9 | * 2022, Technische Universität Berlin
10 | * Prof. Guillermo Gallego
11 | * Robotic Interactive Perception
12 | * Marchstrasse 23, Sekr. MAR 5-5
13 | * 10587 Berlin, Germany
14 | */
15 |
16 | #pragma once
17 |
18 | #include
19 | #include
20 | #include
21 | #include
22 |
23 | // Calibration functions TEMPORARY. They should be read from input files
24 |
25 | void loadCalibInfo(const std::string &cameraSystemDir, bool bPrintCalibInfo);
26 |
27 |
28 | void get_camera_calib_yaml_m3ed(image_geometry::PinholeCameraModel& cam0,
29 | image_geometry::PinholeCameraModel& cam1,
30 | Eigen::Matrix4d& mat4_1_0,
31 | Eigen::Matrix4d& mat4_hand_eye,
32 | std::string calib_path);
33 |
34 | void get_camera_calib_dsec_yaml(image_geometry::PinholeCameraModel& cam0,
35 | image_geometry::PinholeCameraModel& cam1,
36 | Eigen::Matrix4d& mat4_1_0,
37 | Eigen::Matrix4d& mat4_hand_eye,
38 | std::string calib_path,
39 | std::string mocap_calib_path);
40 |
41 | void get_camera_calib_dsec_zurich04a(image_geometry::PinholeCameraModel& cam0,
42 | image_geometry::PinholeCameraModel& cam1,
43 | Eigen::Matrix4d& matR_L,
44 | Eigen::Matrix4d& mat4_hand_eye,
45 | std::string calib_path);
46 |
47 | void get_camera_calib_dsec_interlaken00b(image_geometry::PinholeCameraModel& cam0,
48 | image_geometry::PinholeCameraModel& cam1,
49 | Eigen::Matrix4d& matR_L,
50 | Eigen::Matrix4d& mat4_hand_eye,
51 | std::string calib_path);
52 | void get_camera_calib_yaml(image_geometry::PinholeCameraModel& cam0,
53 | image_geometry::PinholeCameraModel& cam1,
54 | Eigen::Matrix4d& mat4_1_0,
55 | Eigen::Matrix4d& mat4_hand_eye,
56 | std::string calib_path);
57 |
58 | void get_camera_calib_json(image_geometry::PinholeCameraModel& cam0,
59 | image_geometry::PinholeCameraModel& cam1,
60 | Eigen::Matrix4d& mat4_1_0,
61 | Eigen::Matrix4d& mat4_hand_eye,
62 | std::string calib_pathA,
63 | std::string calib_pathB);
64 |
65 | void get_camera_calib_slider(image_geometry::PinholeCameraModel& cam0,
66 | image_geometry::PinholeCameraModel& cam1,
67 | Eigen::Matrix4d& mat4_1_0,
68 | Eigen::Matrix4d& mat4_hand_eye,
69 | std::string calib_path);
70 |
71 | void get_camera_calib_hkust(image_geometry::PinholeCameraModel& cam0,
72 | image_geometry::PinholeCameraModel& cam1,
73 | Eigen::Matrix4d& mat4_1_0,
74 | Eigen::Matrix4d& mat4_hand_eye,
75 | std::string calib_path);
76 |
77 | void get_camera_calib_evimo2(image_geometry::PinholeCameraModel& cam0,
78 | image_geometry::PinholeCameraModel& cam1,
79 | image_geometry::PinholeCameraModel& cam2,
80 | Eigen::Matrix4d& mat4_1_0,
81 | Eigen::Matrix4d& mat4_2_0,
82 | Eigen::Matrix4d& mat4_hand_eye,
83 | std::string calib_path);
84 |
85 | void get_camera_calib_yaml_mvsec(image_geometry::PinholeCameraModel& cam0,
86 | image_geometry::PinholeCameraModel& cam1,
87 | Eigen::Matrix4d& mat4_1_0,
88 | Eigen::Matrix4d& mat4_hand_eye,
89 | std::string calib_path);
90 |
91 | void get_camera_calib_ESIM(image_geometry::PinholeCameraModel& cam0,
92 | image_geometry::PinholeCameraModel& cam1,
93 | Eigen::Matrix4d& mat4_1_0,
94 | Eigen::Matrix4d& mat4_hand_eye);
95 |
96 | // rpg_DAVIS_stereo dataset (Joey ECCV'18)
97 | void get_camera_calib_ECCV18(image_geometry::PinholeCameraModel& cam0,
98 | image_geometry::PinholeCameraModel& cam1,
99 | Eigen::Matrix4d& mat4_1_0,
100 | Eigen::Matrix4d& mat4_hand_eye);
101 |
102 | // Samsung DVS Gen3 stereo
103 | void get_camera_calib_DVS_Gen3(image_geometry::PinholeCameraModel& cam0,
104 | image_geometry::PinholeCameraModel& cam1,
105 | Eigen::Matrix4d& mat4_1_0,
106 | Eigen::Matrix4d& mat4_hand_eye);
107 |
108 | void get_camera_calib_sony(image_geometry::PinholeCameraModel& cam0,
109 | image_geometry::PinholeCameraModel& cam1,
110 | Eigen::Matrix4d& mat4_1_0,
111 | Eigen::Matrix4d& mat4_hand_eye,
112 | std::string calib_path,
113 | std::string mocap_calib_path);
114 |
--------------------------------------------------------------------------------
/mapper_emvs_stereo/include/mapper_emvs_stereo/data_loading.hpp:
--------------------------------------------------------------------------------
1 | /*
2 | * \file data_loading.hpp
3 | * \brief header for functions to load events and poses from ROSBags
4 | * \author (1) Suman Ghosh
5 | * \date 2022-09-01
6 | * \author (2) Guillermo Gallego
7 | * \date 2022-09-01
8 | * Copyright/Rights of Use:
9 | * 2022, Technische Universität Berlin
10 | * Prof. Guillermo Gallego
11 | * Robotic Interactive Perception
12 | * Marchstrasse 23, Sekr. MAR 5-5
13 | * 10587 Berlin, Germany
14 | */
15 |
16 |
17 | #pragma once
18 |
19 | #include
20 | #include