keypoint.hpp
Go to the documentation of this file.
00001 #ifndef __fovis_keypoint_hpp__
00002 #define __fovis_keypoint_hpp__
00003 
00004 #include <inttypes.h>
00005 
00006 #include <Eigen/Core>
00007 
00008 namespace fovis
00009 {
00010 
00014 class KeyPoint
00015 {
00016   public:
00020     float u;
00024     float v;
00029     float score;
00030 
00034     KeyPoint() : u(0), v(0), score(0) {}
00035 
00039     KeyPoint(float u_, float v_, float score_) : u(u_), v(v_), score(score_) {}
00040 };
00041 
00049 class KeypointData
00050 {
00051   public:
00052     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00053   public:
00054 
00058     KeyPoint kp;
00059 
00063     Eigen::Vector4d xyzw;
00064 
00068     bool has_depth;
00069 
00075     Eigen::Vector3d xyz;
00076 
00080     Eigen::Vector2d base_uv;
00081 
00085     Eigen::Vector2d rect_base_uv;
00086 
00098     float disparity;
00099 
00103     uint8_t pyramid_level;
00104 
00108     int keypoint_index;
00109 
00113     int track_id;
00114 
00118     KeypointData() :
00119       kp(0, 0, 0),
00120       xyzw(0, 0, 0, 1),
00121       has_depth (false),
00122       xyz(0, 0, 0),
00123       base_uv(0, 0),
00124       rect_base_uv(0, 0),
00125       disparity(NAN),
00126       pyramid_level(0),
00127       keypoint_index(0),
00128       track_id(0)
00129     {}
00130 
00134     void copyFrom(const KeypointData& src) {
00135       kp.u = src.kp.u;
00136       kp.v = src.kp.v;
00137       kp.score = src.kp.score;
00138       xyzw = src.xyzw;
00139       xyz = src.xyz;
00140       has_depth = src.has_depth;
00141       base_uv = src.base_uv;
00142       rect_base_uv = src.rect_base_uv;
00143       disparity = NAN;
00144       pyramid_level = src.pyramid_level;
00145       keypoint_index = src.keypoint_index;
00146       track_id = src.track_id;
00147     }
00148 };
00149 
00150 }
00151 #endif


libfovis
Author(s): Albert Huang, Maurice Fallon
autogenerated on Thu Jun 6 2019 20:16:12