$search

P::ODetect3D Class Reference

#include <ODetect3D.hh>

List of all members.

Classes

class  Point2D
class  Point3D

Public Member Functions

bool Detect (Array< KeypointDescriptor * > &keys, Object3D &object)
void DrawInlier (IplImage *img, CvScalar col)
 ODetect3D ()
void SetCameraParameter (CvMat *C)
void SetDebugImage (IplImage *img)
void setNNThreshold (double nn_threshold)
void setNPointsToMatch (unsigned int n)
 ~ODetect3D ()

Private Member Functions

void ComputeConfidence (Array< KeypointDescriptor * > &keys, unsigned &numInl, Object3D &object)
void CopyPoseCv (PoseCv &in, PoseCv &out)
void DeletePairs (Array< KeyClusterPair * > &matches)
void FitModelRANSAC (Array< KeyClusterPair * > &matches, PoseCv &pose, unsigned &numInl)
bool GetBestCorner (PoseCv &pose, KeypointDescriptor *k, CodebookEntry *cbe, Point3D &pos, double &minDist)
void GetInlier (Array< KeyClusterPair * > &matches, PoseCv &pose, int &inl)
void GetRandIdx (unsigned size, unsigned num, P::Array< unsigned > &idx)
void MatchKeypoints (Array< KeypointDescriptor * > &keys, Array< CodebookEntry * > &cb, Array< KeyClusterPair * > &matches)
void MatchKeypoints2 (Array< KeypointDescriptor * > &keys, Array< CodebookEntry * > &cb, Array< KeyClusterPair * > &matches)
void MatchKeypointsGPU (Array< KeypointDescriptor * > &keys, Array< CodebookEntry * > &cb, Array< KeyClusterPair * > &matches)
void ProjectPoint2Image (double xc, double yc, double zc, CvMat *C, double &xi, double &yi)
void RefinePoseLS (Array< KeyClusterPair * > &matches, PoseCv &pose, unsigned &inl, double &err)

Private Attributes

CvMat * cameraMatrix
IplImage * dbg
CvMat * distCoeffs
Array< KeypointDescriptor * > inlier
SiftMatchGPU * matcher
int matcherSize
Array< KeyClusterPair * > matches
unsigned int n_points_to_match
double nn_far_enough_threshold

Detailed Description

Definition at line 25 of file ODetect3D.hh.


Constructor & Destructor Documentation

P::ODetect3D::ODetect3D (  ) 

Definition at line 26 of file ODetect3D.cc.

P::ODetect3D::~ODetect3D (  ) 

Definition at line 46 of file ODetect3D.cc.


Member Function Documentation

void P::ODetect3D::ComputeConfidence ( Array< KeypointDescriptor * > &  keys,
unsigned &  numInl,
Object3D object 
) [private]

ComputeConfidence

Definition at line 437 of file ODetect3D.cc.

void P::ODetect3D::CopyPoseCv ( PoseCv in,
PoseCv out 
) [inline, private]

Definition at line 114 of file ODetect3D.hh.

void P::ODetect3D::DeletePairs ( Array< KeyClusterPair * > &  matches  )  [private]

DeletePairs

Definition at line 57 of file ODetect3D.cc.

bool P::ODetect3D::Detect ( Array< KeypointDescriptor * > &  keys,
Object3D object 
)

Simple RANSAC based 3d object detector

Definition at line 480 of file ODetect3D.cc.

void P::ODetect3D::DrawInlier ( IplImage *  img,
CvScalar  col 
)

Draw inlier stored during recognition. Attention: Pointers are stored! DrawInlier only works as long as image keypoints are valid!

Definition at line 572 of file ODetect3D.cc.

void P::ODetect3D::FitModelRANSAC ( Array< KeyClusterPair * > &  matches,
PoseCv pose,
unsigned &  numInl 
) [private]

Verify object model

Definition at line 233 of file ODetect3D.cc.

bool P::ODetect3D::GetBestCorner ( PoseCv pose,
KeypointDescriptor k,
CodebookEntry cbe,
Point3D pos,
double &  minDist 
) [private]

Get best supporting corner of a matching codebook entry

Definition at line 321 of file ODetect3D.cc.

void P::ODetect3D::GetInlier ( Array< KeyClusterPair * > &  matches,
PoseCv pose,
int &  inl 
) [private]

Count inlier

Definition at line 191 of file ODetect3D.cc.

void P::ODetect3D::GetRandIdx ( unsigned  size,
unsigned  num,
P::Array< unsigned > &  idx 
) [private]

GetRandIdx

Definition at line 175 of file ODetect3D.cc.

void P::ODetect3D::MatchKeypoints ( Array< KeypointDescriptor * > &  keys,
Array< CodebookEntry * > &  cb,
Array< KeyClusterPair * > &  matches 
) [private]

Match keypoints with codebook (use threshold)

Definition at line 111 of file ODetect3D.cc.

void P::ODetect3D::MatchKeypoints2 ( Array< KeypointDescriptor * > &  keys,
Array< CodebookEntry * > &  cb,
Array< KeyClusterPair * > &  matches 
) [private]

Match keypoints with codebook check second nearest neighbour

Definition at line 69 of file ODetect3D.cc.

void P::ODetect3D::MatchKeypointsGPU ( Array< KeypointDescriptor * > &  keys,
Array< CodebookEntry * > &  cb,
Array< KeyClusterPair * > &  matches 
) [private]

Match keypoints (GPU version)

Definition at line 141 of file ODetect3D.cc.

void P::ODetect3D::ProjectPoint2Image ( double  xc,
double  yc,
double  zc,
CvMat *  C,
double &  xi,
double &  yi 
) [inline, private]

ProjectPoint2Image projects a 3d point to the image

Definition at line 107 of file ODetect3D.hh.

void P::ODetect3D::RefinePoseLS ( Array< KeyClusterPair * > &  matches,
PoseCv pose,
unsigned &  inl,
double &  err 
) [private]

Compute least squares pose

Definition at line 356 of file ODetect3D.cc.

void P::ODetect3D::SetCameraParameter ( CvMat *  C  ) 

Set camera intrinsic parameter We assume undistort images!!! Keypoints must be undistort!!!!

Parameters:
_C Camera intrinsic matrix of undistort images

Definition at line 562 of file ODetect3D.cc.

void P::ODetect3D::SetDebugImage ( IplImage *  img  )  [inline]

Definition at line 86 of file ODetect3D.hh.

void P::ODetect3D::setNNThreshold ( double  nn_threshold  )  [inline]

Definition at line 91 of file ODetect3D.hh.

void P::ODetect3D::setNPointsToMatch ( unsigned int  n  )  [inline]

Definition at line 96 of file ODetect3D.hh.


Member Data Documentation

CvMat* P::ODetect3D::cameraMatrix [private]

Definition at line 45 of file ODetect3D.hh.

IplImage* P::ODetect3D::dbg [private]

Definition at line 43 of file ODetect3D.hh.

CvMat* P::ODetect3D::distCoeffs [private]

Definition at line 46 of file ODetect3D.hh.

Definition at line 51 of file ODetect3D.hh.

SiftMatchGPU* P::ODetect3D::matcher [private]

Definition at line 48 of file ODetect3D.hh.

Definition at line 49 of file ODetect3D.hh.

Definition at line 74 of file ODetect3D.hh.

unsigned int P::ODetect3D::n_points_to_match [private]

Definition at line 76 of file ODetect3D.hh.

Definition at line 75 of file ODetect3D.hh.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


blort
Author(s): Michael Zillich, Thomas Mörwald, Johann Prankl, Andreas Richtsfeld, Bence Magyar (ROS version)
autogenerated on Fri Mar 1 16:57:58 2013