-
Notifications
You must be signed in to change notification settings - Fork 54
/
Copy pathmain_vo_sf_imageseq.cpp
99 lines (82 loc) · 3.11 KB
/
main_vo_sf_imageseq.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
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
/*********************************************************************************
**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:
// You need to click on the window of the 3D Scene to be able to interact with it.
// 'n' - Load new frame and solve
// 's' - Turn on/off continuous estimation
// 'e' - Finish/exit
// -------------------------------------------------------------------------------
int main()
{
const unsigned int res_factor = 2;
VO_SF cf(res_factor);
//Set first image to load, decimation factor and the sequence dir
unsigned int im_count = 1;
const unsigned int decimation = 1; //5
std::string dir = ".../data/sequence people moving/";
//Load image and create pyramid
cf.loadImageFromSequence(dir, im_count, res_factor);
cf.createImagePyramid();
//Create the 3D Scene
cf.initializeSceneImageSeq();
//Auxiliary variables
int pushed_key = 0;
bool continuous_exec = false, stop = false;
while (!stop)
{
if (cf.window.keyHit())
pushed_key = cf.window.getPushedKey();
else
pushed_key = 0;
switch (pushed_key) {
//Load new image and solve
case 'n':
im_count += decimation;
stop = cf.loadImageFromSequence(dir, im_count, res_factor);
cf.run_VO_SF(true);
cf.createImagesOfSegmentations();
cf.updateSceneImageSeq();
break;
//Start/Stop continuous estimation
case 's':
continuous_exec = !continuous_exec;
break;
//Close the program
case 'e':
stop = true;
break;
}
if ((continuous_exec)&&(!stop))
{
im_count += decimation;
stop = cf.loadImageFromSequence(dir, im_count, res_factor);
cf.run_VO_SF(true);
cf.createImagesOfSegmentations();
cf.updateSceneImageSeq();
}
}
return 0;
}