-
Notifications
You must be signed in to change notification settings - Fork 0
/
DifOdometry_Camera.h
74 lines (54 loc) · 1.67 KB
/
DifOdometry_Camera.h
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
#include <CDifodo.h>
#include <mrpt/utils/CConfigFileBase.h>
#include <mrpt/utils/CImage.h>
#include <mrpt/utils/CTicTac.h>
#include <mrpt/utils/round.h>
#include <mrpt/opengl/COpenGLScene.h>
#include <mrpt/gui/CDisplayWindow3D.h>
#include <iostream>
#include <OpenNI.h>
#include "legend.xpm"
class CDifodoCamera : public CDifodo {
public:
mrpt::gui::CDisplayWindow3D window;
std::ofstream f_res;
bool save_results;
/** Constructor. */
CDifodoCamera() : CDifodo()
{
save_results = 0;
}
/** Initialize the visual odometry method */
void loadConfiguration( const mrpt::utils::CConfigFileBase &ini );
/** Open camera */
bool openCamera();
/** Close camera */
void closeCamera();
/** Capture a new depth frame */
void loadFrame();
/** Create a file to save the estimated trajectory */
void CreateResultsFile();
/** Initialize opengl scene */
void initializeScene();
/** Refresh the opengl scene */
void updateScene();
/** A pre-step that should be performed before starting to estimate the camera velocity.
* It can also be called to reset the estimated trajectory and pose */
void reset();
/** Save the pose estimation following the format of the TUM datasets:
*
* 'timestamp tx ty tz qx qy qz qw'
*
* Please visit http://vision.in.tum.de/data/datasets/rgbd-dataset/file_formats for further details.*/
void writeTrajectoryFile();
private:
unsigned int repr_level;
mrpt::opengl::COpenGLScenePtr scene; //!< Opengl scene
// OpenNI variables to manage the camera
openni::Status rc;
openni::Device device;
openni::VideoMode video_options;
openni::VideoStream depth_ch;
/** Clock used to save the timestamp */
mrpt::utils::CTicTac clock;
};