Classes | Public Member Functions | Private Member Functions | Private Attributes
Matcher Class Reference

#include <matcher.h>

List of all members.

Classes

struct  delta
struct  maximum
struct  p_match
struct  parameters
struct  range

Public Member Functions

void bucketFeatures (int32_t max_features, float bucket_width, float bucket_height)
float getGain (std::vector< int32_t > inliers)
std::vector< Matcher::p_matchgetMatches ()
 Matcher (parameters param)
void matchFeatures (int32_t method, Matrix *Tr_delta=0)
void pushBack (uint8_t *I1, uint8_t *I2, int32_t *dims, const bool replace)
void pushBack (uint8_t *I1, int32_t *dims, const bool replace)
void setIntrinsics (double f, double cu, double cv, double base)
void setMatches (std::vector< Matcher::p_match > p_matched)
 ~Matcher ()

Private Member Functions

void computeDescriptor (const uint8_t *I_du, const uint8_t *I_dv, const int32_t &bpl, const int32_t &u, const int32_t &v, uint8_t *desc_addr)
void computeDescriptors (uint8_t *I_du, uint8_t *I_dv, const int32_t bpl, std::vector< Matcher::maximum > &maxima)
void computeFeatures (uint8_t *I, const int32_t *dims, int32_t *&max1, int32_t &num1, int32_t *&max2, int32_t &num2, uint8_t *&I_du, uint8_t *&I_dv, uint8_t *&I_du_full, uint8_t *&I_dv_full)
void computePriorStatistics (std::vector< Matcher::p_match > &p_matched, int32_t method)
void computeSmallDescriptor (const uint8_t *I_du, const uint8_t *I_dv, const int32_t &bpl, const int32_t &u, const int32_t &v, uint8_t *desc_addr)
uint8_t * createHalfResolutionImage (uint8_t *I, const int32_t *dims)
void createIndexVector (int32_t *m, int32_t n, std::vector< int32_t > *k, const int32_t &u_bin_num, const int32_t &v_bin_num)
void filterImageAll (uint8_t *I, uint8_t *I_du, uint8_t *I_dv, int16_t *I_f1, int16_t *I_f2, const int *dims)
void filterImageSobel (uint8_t *I, uint8_t *I_du, uint8_t *I_dv, const int *dims)
void findMatch (int32_t *m1, const int32_t &i1, int32_t *m2, const int32_t &step_size, std::vector< int32_t > *k2, const int32_t &u_bin_num, const int32_t &v_bin_num, const int32_t &stat_bin, int32_t &min_ind, int32_t stage, bool flow, bool use_prior, double u_=-1, double v_=-1)
int32_t getAddressOffsetImage (const int32_t &u, const int32_t &v, const int32_t &width)
void getHalfResolutionDimensions (const int32_t *dims, int32_t *dims_half)
void matching (int32_t *m1p, int32_t *m2p, int32_t *m1c, int32_t *m2c, int32_t n1p, int32_t n2p, int32_t n1c, int32_t n2c, std::vector< Matcher::p_match > &p_matched, int32_t method, bool use_prior, Matrix *Tr_delta=0)
float mean (const uint8_t *I, const int32_t &bpl, const int32_t &u_min, const int32_t &u_max, const int32_t &v_min, const int32_t &v_max)
void nonMaximumSuppression (int16_t *I_f1, int16_t *I_f2, const int32_t *dims, std::vector< Matcher::maximum > &maxima, int32_t nms_n)
bool parabolicFitting (const uint8_t *I1_du, const uint8_t *I1_dv, const int32_t *dims1, const uint8_t *I2_du, const uint8_t *I2_dv, const int32_t *dims2, const float &u1, const float &v1, float &u2, float &v2, Matrix At, Matrix AtA, uint8_t *desc_buffer)
void refinement (std::vector< Matcher::p_match > &p_matched, int32_t method)
void relocateMinimum (const uint8_t *I1_du, const uint8_t *I1_dv, const int32_t *dims1, const uint8_t *I2_du, const uint8_t *I2_dv, const int32_t *dims2, const float &u1, const float &v1, float &u2, float &v2, uint8_t *desc_buffer)
void removeOutliers (std::vector< Matcher::p_match > &p_matched, int32_t method)
uint8_t saturate (int16_t in)

Private Attributes

int32_t dims_c [3]
int32_t dims_p [3]
uint8_t * I1c
uint8_t * I1c_du
uint8_t * I1c_du_full
uint8_t * I1c_dv
uint8_t * I1c_dv_full
uint8_t * I1p
uint8_t * I1p_du
uint8_t * I1p_du_full
uint8_t * I1p_dv
uint8_t * I1p_dv_full
uint8_t * I2c
uint8_t * I2c_du
uint8_t * I2c_du_full
uint8_t * I2c_dv
uint8_t * I2c_dv_full
uint8_t * I2p
uint8_t * I2p_du
uint8_t * I2p_du_full
uint8_t * I2p_dv
uint8_t * I2p_dv_full
int32_t * m1c1
int32_t * m1c2
int32_t * m1p1
int32_t * m1p2
int32_t * m2c1
int32_t * m2c2
int32_t * m2p1
int32_t * m2p2
int32_t margin
int32_t n1c1
int32_t n1c2
int32_t n1p1
int32_t n1p2
int32_t n2c1
int32_t n2c2
int32_t n2p1
int32_t n2p2
std::vector< Matcher::p_matchp_matched_1
std::vector< Matcher::p_matchp_matched_2
parameters param
std::vector< Matcher::rangeranges

Detailed Description

Definition at line 36 of file matcher.h.


Constructor & Destructor Documentation

Definition at line 33 of file matcher.cpp.

Definition at line 64 of file matcher.cpp.


Member Function Documentation

void Matcher::bucketFeatures ( int32_t  max_features,
float  bucket_width,
float  bucket_height 
)

Definition at line 252 of file matcher.cpp.

void Matcher::computeDescriptor ( const uint8_t *  I_du,
const uint8_t *  I_dv,
const int32_t &  bpl,
const int32_t &  u,
const int32_t &  v,
uint8_t *  desc_addr 
) [inline, private]

Definition at line 442 of file matcher.cpp.

void Matcher::computeDescriptors ( uint8_t *  I_du,
uint8_t *  I_dv,
const int32_t  bpl,
std::vector< Matcher::maximum > &  maxima 
) [private]

Definition at line 519 of file matcher.cpp.

void Matcher::computeFeatures ( uint8_t *  I,
const int32_t *  dims,
int32_t *&  max1,
int32_t &  num1,
int32_t *&  max2,
int32_t &  num2,
uint8_t *&  I_du,
uint8_t *&  I_dv,
uint8_t *&  I_du_full,
uint8_t *&  I_dv_full 
) [private]

Definition at line 660 of file matcher.cpp.

void Matcher::computePriorStatistics ( std::vector< Matcher::p_match > &  p_matched,
int32_t  method 
) [private]

Definition at line 749 of file matcher.cpp.

void Matcher::computeSmallDescriptor ( const uint8_t *  I_du,
const uint8_t *  I_dv,
const int32_t &  bpl,
const int32_t &  u,
const int32_t &  v,
uint8_t *  desc_addr 
) [inline, private]

Definition at line 490 of file matcher.cpp.

uint8_t * Matcher::createHalfResolutionImage ( uint8_t *  I,
const int32_t *  dims 
) [private]

Definition at line 647 of file matcher.cpp.

void Matcher::createIndexVector ( int32_t *  m,
int32_t  n,
std::vector< int32_t > *  k,
const int32_t &  u_bin_num,
const int32_t &  v_bin_num 
) [private]

Definition at line 886 of file matcher.cpp.

void Matcher::filterImageAll ( uint8_t *  I,
uint8_t *  I_du,
uint8_t *  I_dv,
int16_t *  I_f1,
int16_t *  I_f2,
const int *  dims 
) [private]

Definition at line 540 of file matcher.cpp.

void Matcher::filterImageSobel ( uint8_t *  I,
uint8_t *  I_du,
uint8_t *  I_dv,
const int *  dims 
) [private]

Definition at line 605 of file matcher.cpp.

void Matcher::findMatch ( int32_t *  m1,
const int32_t &  i1,
int32_t *  m2,
const int32_t &  step_size,
std::vector< int32_t > *  k2,
const int32_t &  u_bin_num,
const int32_t &  v_bin_num,
const int32_t &  stat_bin,
int32_t &  min_ind,
int32_t  stage,
bool  flow,
bool  use_prior,
double  u_ = -1,
double  v_ = -1 
) [inline, private]

Definition at line 907 of file matcher.cpp.

int32_t Matcher::getAddressOffsetImage ( const int32_t &  u,
const int32_t &  v,
const int32_t &  width 
) [inline, private]

Definition at line 176 of file matcher.h.

float Matcher::getGain ( std::vector< int32_t >  inliers)

Definition at line 295 of file matcher.cpp.

void Matcher::getHalfResolutionDimensions ( const int32_t *  dims,
int32_t *  dims_half 
) [private]

Definition at line 641 of file matcher.cpp.

std::vector<Matcher::p_match> Matcher::getMatches ( ) [inline]

Definition at line 138 of file matcher.h.

void Matcher::matchFeatures ( int32_t  method,
Matrix Tr_delta = 0 
)

Definition at line 187 of file matcher.cpp.

void Matcher::matching ( int32_t *  m1p,
int32_t *  m2p,
int32_t *  m1c,
int32_t *  m2c,
int32_t  n1p,
int32_t  n2p,
int32_t  n1c,
int32_t  n2c,
std::vector< Matcher::p_match > &  p_matched,
int32_t  method,
bool  use_prior,
Matrix Tr_delta = 0 
) [private]

Definition at line 989 of file matcher.cpp.

float Matcher::mean ( const uint8_t *  I,
const int32_t &  bpl,
const int32_t &  u_min,
const int32_t &  u_max,
const int32_t &  v_min,
const int32_t &  v_max 
) [inline, private]

Definition at line 1625 of file matcher.cpp.

void Matcher::nonMaximumSuppression ( int16_t *  I_f1,
int16_t *  I_f2,
const int32_t *  dims,
std::vector< Matcher::maximum > &  maxima,
int32_t  nms_n 
) [private]

Definition at line 339 of file matcher.cpp.

bool Matcher::parabolicFitting ( const uint8_t *  I1_du,
const uint8_t *  I1_dv,
const int32_t *  dims1,
const uint8_t *  I2_du,
const uint8_t *  I2_dv,
const int32_t *  dims2,
const float &  u1,
const float &  v1,
float &  u2,
float &  v2,
Matrix  At,
Matrix  AtA,
uint8_t *  desc_buffer 
) [private]

Definition at line 1416 of file matcher.cpp.

void Matcher::pushBack ( uint8_t *  I1,
uint8_t *  I2,
int32_t *  dims,
const bool  replace 
)

Definition at line 95 of file matcher.cpp.

void Matcher::pushBack ( uint8_t *  I1,
int32_t *  dims,
const bool  replace 
) [inline]

Definition at line 125 of file matcher.h.

void Matcher::refinement ( std::vector< Matcher::p_match > &  p_matched,
int32_t  method 
) [private]

Definition at line 1533 of file matcher.cpp.

void Matcher::relocateMinimum ( const uint8_t *  I1_du,
const uint8_t *  I1_dv,
const int32_t *  dims1,
const uint8_t *  I2_du,
const uint8_t *  I2_dv,
const int32_t *  dims2,
const float &  u1,
const float &  v1,
float &  u2,
float &  v2,
uint8_t *  desc_buffer 
) [private]

Definition at line 1492 of file matcher.cpp.

void Matcher::removeOutliers ( std::vector< Matcher::p_match > &  p_matched,
int32_t  method 
) [private]

Definition at line 1244 of file matcher.cpp.

uint8_t Matcher::saturate ( int16_t  in) [inline, private]

Definition at line 534 of file matcher.cpp.

void Matcher::setIntrinsics ( double  f,
double  cu,
double  cv,
double  base 
) [inline]

Definition at line 77 of file matcher.h.

void Matcher::setMatches ( std::vector< Matcher::p_match p_matched) [inline]

Definition at line 139 of file matcher.h.


Member Data Documentation

int32_t Matcher::dims_c[3] [private]

Definition at line 248 of file matcher.h.

int32_t Matcher::dims_p[3] [private]

Definition at line 248 of file matcher.h.

uint8_t * Matcher::I1c [private]

Definition at line 243 of file matcher.h.

uint8_t * Matcher::I1c_du [private]

Definition at line 244 of file matcher.h.

uint8_t * Matcher::I1c_du_full [private]

Definition at line 246 of file matcher.h.

uint8_t * Matcher::I1c_dv [private]

Definition at line 245 of file matcher.h.

uint8_t * Matcher::I1c_dv_full [private]

Definition at line 247 of file matcher.h.

uint8_t* Matcher::I1p [private]

Definition at line 243 of file matcher.h.

uint8_t* Matcher::I1p_du [private]

Definition at line 244 of file matcher.h.

uint8_t* Matcher::I1p_du_full [private]

Definition at line 246 of file matcher.h.

uint8_t* Matcher::I1p_dv [private]

Definition at line 245 of file matcher.h.

uint8_t* Matcher::I1p_dv_full [private]

Definition at line 247 of file matcher.h.

uint8_t * Matcher::I2c [private]

Definition at line 243 of file matcher.h.

uint8_t * Matcher::I2c_du [private]

Definition at line 244 of file matcher.h.

uint8_t * Matcher::I2c_du_full [private]

Definition at line 246 of file matcher.h.

uint8_t * Matcher::I2c_dv [private]

Definition at line 245 of file matcher.h.

uint8_t * Matcher::I2c_dv_full [private]

Definition at line 247 of file matcher.h.

uint8_t * Matcher::I2p [private]

Definition at line 243 of file matcher.h.

uint8_t * Matcher::I2p_du [private]

Definition at line 244 of file matcher.h.

uint8_t * Matcher::I2p_du_full [private]

Definition at line 246 of file matcher.h.

uint8_t * Matcher::I2p_dv [private]

Definition at line 245 of file matcher.h.

uint8_t * Matcher::I2p_dv_full [private]

Definition at line 247 of file matcher.h.

int32_t * Matcher::m1c1 [private]

Definition at line 239 of file matcher.h.

int32_t * Matcher::m1c2 [private]

Definition at line 240 of file matcher.h.

int32_t* Matcher::m1p1 [private]

Definition at line 239 of file matcher.h.

int32_t* Matcher::m1p2 [private]

Definition at line 240 of file matcher.h.

int32_t * Matcher::m2c1 [private]

Definition at line 239 of file matcher.h.

int32_t * Matcher::m2c2 [private]

Definition at line 240 of file matcher.h.

int32_t * Matcher::m2p1 [private]

Definition at line 239 of file matcher.h.

int32_t * Matcher::m2p2 [private]

Definition at line 240 of file matcher.h.

int32_t Matcher::margin [private]

Definition at line 237 of file matcher.h.

int32_t Matcher::n1c1 [private]

Definition at line 241 of file matcher.h.

int32_t Matcher::n1c2 [private]

Definition at line 242 of file matcher.h.

int32_t Matcher::n1p1 [private]

Definition at line 241 of file matcher.h.

int32_t Matcher::n1p2 [private]

Definition at line 242 of file matcher.h.

int32_t Matcher::n2c1 [private]

Definition at line 241 of file matcher.h.

int32_t Matcher::n2c2 [private]

Definition at line 242 of file matcher.h.

int32_t Matcher::n2p1 [private]

Definition at line 241 of file matcher.h.

int32_t Matcher::n2p2 [private]

Definition at line 242 of file matcher.h.

std::vector<Matcher::p_match> Matcher::p_matched_1 [private]

Definition at line 250 of file matcher.h.

std::vector<Matcher::p_match> Matcher::p_matched_2 [private]

Definition at line 251 of file matcher.h.

Definition at line 236 of file matcher.h.

std::vector<Matcher::range> Matcher::ranges [private]

Definition at line 252 of file matcher.h.


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


dlut_libvo
Author(s): Zhuang Yan
autogenerated on Thu Jun 6 2019 20:03:29