1 #ifndef __fovis_keypoint_hpp__
2 #define __fovis_keypoint_hpp__
39 KeyPoint(
float u_,
float v_,
float score_) : u(u_), v(v_), score(score_) {}
52 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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