libfovis
keypoint.hpp
1 #ifndef __fovis_keypoint_hpp__
2 #define __fovis_keypoint_hpp__
3 
4 #include <inttypes.h>
5 
6 #include <Eigen/Core>
7 
8 namespace fovis
9 {
10 
14 class KeyPoint
15 {
16  public:
20  float u;
24  float v;
29  float score;
30 
34  KeyPoint() : u(0), v(0), score(0) {}
35 
39  KeyPoint(float u_, float v_, float score_) : u(u_), v(v_), score(score_) {}
40 };
41 
50 {
51  public:
52  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53  public:
54 
59 
63  Eigen::Vector4d xyzw;
64 
68  bool has_depth;
69 
75  Eigen::Vector3d xyz;
76 
80  Eigen::Vector2d base_uv;
81 
85  Eigen::Vector2d rect_base_uv;
86 
98  float disparity;
99 
103  uint8_t pyramid_level;
104 
109 
113  int track_id;
114 
119  kp(0, 0, 0),
120  xyzw(0, 0, 0, 1),
121  has_depth (false),
122  xyz(0, 0, 0),
123  base_uv(0, 0),
124  rect_base_uv(0, 0),
125  disparity(NAN),
126  pyramid_level(0),
127  keypoint_index(0),
128  track_id(0)
129  {}
130 
134  void copyFrom(const KeypointData& src) {
135  kp.u = src.kp.u;
136  kp.v = src.kp.v;
137  kp.score = src.kp.score;
138  xyzw = src.xyzw;
139  xyz = src.xyz;
140  has_depth = src.has_depth;
141  base_uv = src.base_uv;
142  rect_base_uv = src.rect_base_uv;
143  disparity = NAN;
144  pyramid_level = src.pyramid_level;
145  keypoint_index = src.keypoint_index;
146  track_id = src.track_id;
147  }
148 };
149 
150 }
151 #endif
int keypoint_index
Definition: keypoint.hpp:108
bool has_depth
Definition: keypoint.hpp:68
Eigen::Vector4d xyzw
Definition: keypoint.hpp:63
Eigen::Vector2d base_uv
Definition: keypoint.hpp:80
KeyPoint(float u_, float v_, float score_)
Definition: keypoint.hpp:39
void copyFrom(const KeypointData &src)
Definition: keypoint.hpp:134
Eigen::Vector2d rect_base_uv
Definition: keypoint.hpp:85
float disparity
Definition: keypoint.hpp:98
Image feature used for motion estimation.
Definition: keypoint.hpp:49
int track_id
Definition: keypoint.hpp:113
uint8_t pyramid_level
Definition: keypoint.hpp:103
float score
Definition: keypoint.hpp:29
quick and dirty profiling tool.inspired by the matlab tic/toc command
Definition: camera_intrinsics.hpp:6
float u
Definition: keypoint.hpp:20
An interesting point in an image.
Definition: keypoint.hpp:14
KeyPoint()
Definition: keypoint.hpp:34
Eigen::Vector3d xyz
Definition: keypoint.hpp:75
KeyPoint kp
Definition: keypoint.hpp:58
KeypointData()
Definition: keypoint.hpp:118
float v
Definition: keypoint.hpp:24