forked from MarianoJT88/Joint-VO-SF
-
Notifications
You must be signed in to change notification settings - Fork 0
/
main_vo_sf_imagepair.cpp
64 lines (51 loc) · 2.23 KB
/
main_vo_sf_imagepair.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
/*********************************************************************************
**Fast Odometry and Scene Flow from RGB-D Cameras based on Geometric Clustering **
**------------------------------------------------------------------------------**
** **
** Copyright(c) 2017, Mariano Jaimez Tarifa, University of Malaga & TU Munich **
** Copyright(c) 2017, Christian Kerl, TU Munich **
** Copyright(c) 2017, MAPIR group, University of Malaga **
** Copyright(c) 2017, Computer Vision group, TU Munich **
** **
** This program is free software: you can redistribute it and/or modify **
** it under the terms of the GNU General Public License (version 3) as **
** published by the Free Software Foundation. **
** **
** This program is distributed in the hope that it will be useful, but **
** WITHOUT ANY WARRANTY; without even the implied warranty of **
** MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the **
** GNU General Public License for more details. **
** **
** You should have received a copy of the GNU General Public License **
** along with this program. If not, see <http://www.gnu.org/licenses/>. **
** **
*********************************************************************************/
#include <string.h>
#include "joint_vo_sf.h"
// -------------------------------------------------------------------------------
// Instructions:
// Set the flag "save_results" to true if you want to save the estimated scene
// flow and the static/dynamic segmentation
// -------------------------------------------------------------------------------
int main()
{
const bool save_results = false;
const unsigned int res_factor = 2;
VO_SF cf(res_factor);
//Set image dir
std::string dir = ".../data/opening door/";
//Load images and create both pyramids
cf.loadImagePairFromFiles(dir, res_factor);
//Create the 3D Scene
cf.initializeSceneCamera();
//Run the algorithm
cf.run_VO_SF(false);
cf.createImagesOfSegmentations();
//Update the 3D scene
cf.updateSceneCamera(false);
//Save results?
if (save_results)
cf.saveFlowAndSegmToFile(dir);
mrpt::system::os::getch();
return 0;
}