Public Member Functions | Private Member Functions | Private Attributes | Friends
fovis::PyramidLevel Class Reference

One level of a Gaussian image pyramid. More...

#include <pyramid_level.hpp>

List of all members.

Public Member Functions

const uint8_t * getDescriptor (int i) const
const int * getDescriptorIndexOffsets () const
int getDescriptorLength () const
int getDescriptorStride () const
const uint8_t * getGrayscaleImage () const
int getGrayscaleImageStride () const
int getHeight () const
const std::vector< KeyPoint > & getInitialFeatures () const
const KeyPointgetKeypoint (int i) const
const KeypointDatagetKeypointData (int i) const
KeypointDatagetKeypointData (int i)
float getKeypointRectBaseU (int kp_index) const
const Eigen::Vector2d & getKeypointRectBaseUV (int kp_index) const
float getKeypointRectBaseV (int kp_index) const
const Eigen::Vector4d & getKeypointXYZW (int i) const
int getLevelNum () const
int getNumDetectedKeypoints () const
int getNumKeypoints () const
int getWidth () const
bool isLegalKeypointCoordinate (float x, float y) const
void populateDescriptorAligned (int x, int y, uint8_t *descriptor) const
void populateDescriptorInterp (float x, float y, uint8_t *descriptor) const
void populateDescriptorsAligned (const KeypointData *keypoints, int num_keypoints, uint8_t *descriptors) const
void populateDescriptorsInterp (const KeypointData *keypoints, int num_keypoints, uint8_t *descriptors) const
 PyramidLevel (int width, int height, int level_num, int feature_window_size, GridKeyPointFilter &grid_filter)
 ~PyramidLevel ()

Private Member Functions

void increase_capacity (int new_capacity)

Private Attributes

IntensityDescriptorExtractor_descriptor_extractor
uint8_t * _descriptors
GridKeyPointFilter _grid_filter
int _height
std::vector< KeyPoint_initial_keypoints
int _keypoint_max_x
int _keypoint_max_y
int _keypoint_min_x
int _keypoint_min_y
KeypointData_keypoints
int _keypoints_capacity
int _level_num
int _num_detected_keypoints
int _num_keypoints
uint8_t * _pyrbuf
uint8_t * _raw_gray
int _raw_gray_stride
int _width

Friends

class OdometryFrame
class StereoFrame

Detailed Description

One level of a Gaussian image pyramid.

TODO

Definition at line 21 of file pyramid_level.hpp.


Constructor & Destructor Documentation

fovis::PyramidLevel::PyramidLevel ( int  width,
int  height,
int  level_num,
int  feature_window_size,
GridKeyPointFilter grid_filter 
)

Definition at line 15 of file pyramid_level.cpp.

Definition at line 76 of file pyramid_level.cpp.


Member Function Documentation

const uint8_t* fovis::PyramidLevel::getDescriptor ( int  i) const [inline]

Definition at line 36 of file pyramid_level.hpp.

const int* fovis::PyramidLevel::getDescriptorIndexOffsets ( ) const [inline]

Definition at line 103 of file pyramid_level.hpp.

Definition at line 49 of file pyramid_level.hpp.

Definition at line 41 of file pyramid_level.hpp.

const uint8_t* fovis::PyramidLevel::getGrayscaleImage ( ) const [inline]

Definition at line 28 of file pyramid_level.hpp.

Definition at line 32 of file pyramid_level.hpp.

int fovis::PyramidLevel::getHeight ( ) const [inline]

Definition at line 96 of file pyramid_level.hpp.

const std::vector<KeyPoint>& fovis::PyramidLevel::getInitialFeatures ( ) const [inline]

Definition at line 107 of file pyramid_level.hpp.

const KeyPoint& fovis::PyramidLevel::getKeypoint ( int  i) const [inline]

Definition at line 53 of file pyramid_level.hpp.

const KeypointData* fovis::PyramidLevel::getKeypointData ( int  i) const [inline]

Definition at line 73 of file pyramid_level.hpp.

Definition at line 77 of file pyramid_level.hpp.

float fovis::PyramidLevel::getKeypointRectBaseU ( int  kp_index) const [inline]

Definition at line 61 of file pyramid_level.hpp.

const Eigen::Vector2d& fovis::PyramidLevel::getKeypointRectBaseUV ( int  kp_index) const [inline]

Definition at line 69 of file pyramid_level.hpp.

float fovis::PyramidLevel::getKeypointRectBaseV ( int  kp_index) const [inline]

Definition at line 65 of file pyramid_level.hpp.

const Eigen::Vector4d& fovis::PyramidLevel::getKeypointXYZW ( int  i) const [inline]

Definition at line 57 of file pyramid_level.hpp.

int fovis::PyramidLevel::getLevelNum ( ) const [inline]

Definition at line 81 of file pyramid_level.hpp.

Definition at line 111 of file pyramid_level.hpp.

int fovis::PyramidLevel::getNumKeypoints ( ) const [inline]

Definition at line 45 of file pyramid_level.hpp.

int fovis::PyramidLevel::getWidth ( ) const [inline]

Definition at line 95 of file pyramid_level.hpp.

void fovis::PyramidLevel::increase_capacity ( int  new_capacity) [private]

Definition at line 60 of file pyramid_level.cpp.

bool fovis::PyramidLevel::isLegalKeypointCoordinate ( float  x,
float  y 
) const [inline]

Definition at line 98 of file pyramid_level.hpp.

void fovis::PyramidLevel::populateDescriptorAligned ( int  x,
int  y,
uint8_t *  descriptor 
) const

Definition at line 97 of file pyramid_level.cpp.

void fovis::PyramidLevel::populateDescriptorInterp ( float  x,
float  y,
uint8_t *  descriptor 
) const

Definition at line 91 of file pyramid_level.cpp.

void fovis::PyramidLevel::populateDescriptorsAligned ( const KeypointData keypoints,
int  num_keypoints,
uint8_t *  descriptors 
) const

Definition at line 112 of file pyramid_level.cpp.

void fovis::PyramidLevel::populateDescriptorsInterp ( const KeypointData keypoints,
int  num_keypoints,
uint8_t *  descriptors 
) const

Definition at line 103 of file pyramid_level.cpp.


Friends And Related Function Documentation

friend class OdometryFrame [friend]

Definition at line 116 of file pyramid_level.hpp.

friend class StereoFrame [friend]

Definition at line 117 of file pyramid_level.hpp.


Member Data Documentation

Definition at line 146 of file pyramid_level.hpp.

Definition at line 133 of file pyramid_level.hpp.

Definition at line 127 of file pyramid_level.hpp.

Definition at line 141 of file pyramid_level.hpp.

Definition at line 124 of file pyramid_level.hpp.

Definition at line 137 of file pyramid_level.hpp.

Definition at line 138 of file pyramid_level.hpp.

Definition at line 135 of file pyramid_level.hpp.

Definition at line 136 of file pyramid_level.hpp.

Definition at line 129 of file pyramid_level.hpp.

Definition at line 131 of file pyramid_level.hpp.

Definition at line 142 of file pyramid_level.hpp.

Definition at line 125 of file pyramid_level.hpp.

Definition at line 130 of file pyramid_level.hpp.

uint8_t* fovis::PyramidLevel::_pyrbuf [private]

Definition at line 144 of file pyramid_level.hpp.

uint8_t* fovis::PyramidLevel::_raw_gray [private]

Definition at line 121 of file pyramid_level.hpp.

Definition at line 122 of file pyramid_level.hpp.

Definition at line 140 of file pyramid_level.hpp.


The documentation for this class was generated from the following files:


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