1 #ifndef __fovis_pyramid_level_hpp__
2 #define __fovis_pyramid_level_hpp__
6 #include <Eigen/Geometry>
8 #include "keypoint.hpp"
9 #include "intensity_descriptor.hpp"
10 #include "grid_filter.hpp"
24 PyramidLevel(
int width,
int height,
int level_num,
int feature_window_size,
28 const uint8_t* getGrayscaleImage()
const {
32 int getGrayscaleImageStride()
const {
33 return _raw_gray_stride;
36 const uint8_t* getDescriptor(
int i)
const {
37 return _descriptors + i * getDescriptorStride();
41 int getDescriptorStride()
const {
45 int getNumKeypoints()
const {
46 return _num_keypoints;
49 int getDescriptorLength()
const {
53 const KeyPoint& getKeypoint(
int i)
const {
54 return _keypoints[i].
kp;
57 const Eigen::Vector4d& getKeypointXYZW(
int i)
const {
58 return _keypoints[i].
xyzw;
61 float getKeypointRectBaseU(
int kp_index)
const {
65 float getKeypointRectBaseV(
int kp_index)
const {
69 const Eigen::Vector2d& getKeypointRectBaseUV(
int kp_index)
const {
74 return &_keypoints[i];
78 return &_keypoints[i];
81 int getLevelNum()
const {
return _level_num; }
83 void populateDescriptorInterp(
float x,
float y, uint8_t* descriptor)
const;
85 void populateDescriptorAligned(
int x,
int y, uint8_t* descriptor)
const;
87 void populateDescriptorsInterp(
const KeypointData* keypoints,
89 uint8_t* descriptors)
const;
91 void populateDescriptorsAligned(
const KeypointData* keypoints,
93 uint8_t* descriptors)
const;
95 int getWidth()
const {
return _width; }
96 int getHeight()
const {
return _height; }
98 bool isLegalKeypointCoordinate(
float x,
float y)
const {
99 return x >= _keypoint_min_x && x <= _keypoint_max_x &&
100 y >= _keypoint_min_y && y <= _keypoint_max_y;
103 const int* getDescriptorIndexOffsets()
const {
107 const std::vector<KeyPoint>& getInitialFeatures()
const {
108 return _initial_keypoints;
111 int getNumDetectedKeypoints()
const {
112 return _num_detected_keypoints;
119 void increase_capacity(
int new_capacity);
122 int _raw_gray_stride;
124 std::vector<KeyPoint> _initial_keypoints;
125 int _num_detected_keypoints;
131 int _keypoints_capacity;
133 uint8_t* _descriptors;
Eigen::Vector4d xyzw
Definition: keypoint.hpp:63
Eigen::Vector2d rect_base_uv
Definition: keypoint.hpp:85
Places features into grid cells and discards the weakest features in each cell.
Definition: grid_filter.hpp:14
One level of a Gaussian image pyramid.
Definition: pyramid_level.hpp:21
Stores data specific to an input frame.
Definition: frame.hpp:33
Image feature used for motion estimation.
Definition: keypoint.hpp:49
Stores the right-hand image for a stereo pair.
Definition: stereo_frame.hpp:24
quick and dirty profiling tool.inspired by the matlab tic/toc command
Definition: camera_intrinsics.hpp:6
An interesting point in an image.
Definition: keypoint.hpp:14
KeyPoint kp
Definition: keypoint.hpp:58