-
Notifications
You must be signed in to change notification settings - Fork 0
/
DifOdometry_Camera_main.cpp
198 lines (162 loc) · 4.93 KB
/
DifOdometry_Camera_main.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
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
/* +---------------------------------------------------------------------------+
| Mobile Robot Programming Toolkit (MRPT) |
| http://www.mrpt.org/ |
| |
| Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
| See: http://www.mrpt.org/Authors - All rights reserved. |
| Released under BSD License. See details in http://www.mrpt.org/License |
+---------------------------------------------------------------------------+ */
#include "DifOdometry_Camera.h"
#include <mrpt/system/os.h>
#include <mrpt/utils/CConfigFileMemory.h>
#include <mrpt/utils/CConfigFile.h>
using namespace std;
using namespace mrpt;
const char *default_cfg_txt =
"; ---------------------------------------------------------------\n"
"; FILE: Difodo Parameters.txt\n"
";\n"
"; MJT @ JANUARY-2014\n"
"; ---------------------------------------------------------------\n\n"
"[DIFODO_CONFIG]\n\n"
";cam_mode: 1 - 640x480, 2 - 320x240, 4 - 160x120 \n"
"cam_mode = 2 \n\n"
"Set the frame rate (fps) to 30 or 60 Hz \n"
"fps = 30 \n\n"
";Indicate the number of rows and columns. \n"
"rows = 240 \n"
"cols = 320 \n"
"ctf_levels = 5 \n\n";
// ------------------------------------------------------
// MAIN
// ------------------------------------------------------
int main(int num_arg, char *argv[])
{
try
{
// Read function arguments
//----------------------------------------------------------------------
bool use_config_file = 0;
string filename;
CDifodoCamera odo;
if (num_arg < 2);
else if ( string(argv[1]) == "--help")
{
printf("\n\t Arguments of the function 'main' \n");
printf("==============================================================\n\n");
printf(" --help: Shows this menu... \n\n");
printf(" --config FICH.txt: Load FICH.txt as config file \n\n");
printf(" --create-config FICH.txt: Save the default config parameters \n\n");
printf(" \t\t\t in FICH.txt and close the program \n\n");
printf(" --save-logfile: Enable saving a file with results of the pose estimate \n\n");
system::os::getch();
return 1;
}
else if ( string(argv[1]) == "--create-config")
{
filename = argv[2];
cout << endl << "Config_file name: " << filename;
ofstream new_file(filename.c_str());
new_file << string(default_cfg_txt);
new_file.close();
cout << endl << "File saved" << endl;
system::os::getch();
return 1;
}
else
{
for (int i=1; i<num_arg; i++)
{
if ( string(argv[i]) == "--save-logfile")
{
odo.save_results = 1;
odo.CreateResultsFile();
}
if ( string(argv[i]) == "--config")
{
use_config_file = 1;
filename = argv[i+1];
}
}
}
//Initial steps. Load configuration from file or default, initialize scene and initialize camera
//----------------------------------------------------------------------------------------------
if (use_config_file == 0)
{
utils::CConfigFileMemory configDifodo(default_cfg_txt);
odo.loadConfiguration( configDifodo );
}
else
{
utils::CConfigFile configDifodo(filename);
odo.loadConfiguration( configDifodo );
}
odo.initializeScene();
odo.openCamera();
//==============================================================================
// Main operation
//==============================================================================
int pushed_key = 0;
bool working = 0, stop = 0;
utils::CTicTac main_clock;
main_clock.Tic();
odo.reset();
while (!stop)
{
if (odo.window.keyHit())
pushed_key = odo.window.getPushedKey();
else
pushed_key = 0;
switch (pushed_key) {
//Capture a new depth frame and calculate odometry
case 'n':
odo.loadFrame();
odo.odometryCalculation();
if (odo.save_results == 1)
odo.writeTrajectoryFile();
cout << endl << "Difodo runtime(ms): " << odo.execution_time;
odo.updateScene();
break;
//Start and stop continous odometry
case 's':
working = !working;
break;
//Close the program
case 'e':
stop = 1;
if (odo.f_res.is_open())
odo.f_res.close();
break;
//Reset estimation
case 'r':
odo.reset();
break;
}
if (working == 1)
{
while(main_clock.Tac() < 1.f/float(odo.fps));
if (main_clock.Tac() > 1.05f/float(odo.fps))
cout << endl << "Not enough time to compute everything!!!";
main_clock.Tic();
odo.loadFrame();
odo.odometryCalculation();
if (odo.save_results == 1)
odo.writeTrajectoryFile();
cout << endl << "Difodo runtime(ms): " << odo.execution_time;
odo.updateScene();
}
}
odo.closeCamera();
return 0;
}
catch (std::exception &e)
{
std::cout << "MRPT exception caught: " << e.what() << std::endl;
return -1;
}
catch (...)
{
printf("Untyped exception!!");
return -1;
}
}