pe::PoseEstimator Class Reference

A class that estimates camera pose from features in image frames. More...

#include <pe.h>

Inheritance diagram for pe::PoseEstimator:
Inheritance graph
[legend]

List of all members.

Public Types

enum  MethodType { SFM = 0, PnP = 1, Stereo = 2 }

Public Member Functions

virtual int estimate (const fc::Frame &frame1, const fc::Frame &frame2)
 Uses RANSAC to find best inlier count by finding matches using the provided matcher, optionally polishes the result. Frames must have filled features and descriptors.
virtual int estimate (const fc::Frame &frame1, const fc::Frame &frame2, const std::vector< cv::DMatch > &matches)=0
 Uses RANSAC to find best inlier count from provided matches, optionally polishes the result. Frames must have filled features and descriptors.
MethodType getMethod () const
 Get the method used for inlier detection.
 PoseEstimator (int NRansac, bool LMpolish, double mind, double maxidx, double maxidd)
void setMatcher (const cv::Ptr< cv::DescriptorMatcher > &matcher)
 Set the Descriptor Matcher to use to match features between frames.
void setTestMatches (const std::vector< cv::DMatch > &matches)
void setTestMode (bool mode)
 ~PoseEstimator ()

Public Attributes

std::vector< cv::DMatch > inliers
 RANSAC inliers of matches.
cv::Ptr< cv::DescriptorMatcher > matcher
 Descriptor matcher to use (features_2d::BruteForceMatcher by default).
std::vector< cv::DMatch > matches
 Matches between features in frames.
double maxInlierDDist2
double maxInlierXDist2
 Maximum dist^2 for inliers in pixels.
double minMatchDisp
 Minimum disparity for RANSAC point matches.
int numRansac
 number of RANSAC iterations
bool polish
Eigen::Matrix3d rot
 Rotation matrix of camera between the frames.
Eigen::Vector3d trans
 Translation of the camera between the frames.
MethodType usedMethod
int windowed
 Whether to do windowed or whole-image matching.
int wx
int wy

Protected Member Functions

void matchFrames (const fc::Frame &f0, const fc::Frame &f1, std::vector< cv::DMatch > &fwd_matches)

Protected Attributes

std::vector< cv::DMatch > testMatches
bool testMode

Detailed Description

A class that estimates camera pose from features in image frames.

Definition at line 42 of file pe.h.


Member Enumeration Documentation

Enumerator:
SFM 
PnP 
Stereo 

Definition at line 44 of file pe.h.


Constructor & Destructor Documentation

pe::PoseEstimator::PoseEstimator ( int  NRansac,
bool  LMpolish,
double  mind,
double  maxidx,
double  maxidd 
)

Definition at line 50 of file pe.cpp.

pe::PoseEstimator::~PoseEstimator (  )  [inline]

Definition at line 72 of file pe.h.


Member Function Documentation

virtual int pe::PoseEstimator::estimate ( const fc::Frame &  frame1,
const fc::Frame &  frame2 
) [virtual]

Uses RANSAC to find best inlier count by finding matches using the provided matcher, optionally polishes the result. Frames must have filled features and descriptors.

Reimplemented in pe::PoseEstimator2d, and pe::PoseEstimatorH.

virtual int pe::PoseEstimator::estimate ( const fc::Frame &  frame1,
const fc::Frame &  frame2,
const std::vector< cv::DMatch > &  matches 
) [pure virtual]

Uses RANSAC to find best inlier count from provided matches, optionally polishes the result. Frames must have filled features and descriptors.

Implemented in pe::PoseEstimator2d, pe::PoseEstimator3d, and pe::PoseEstimatorH.

MethodType pe::PoseEstimator::getMethod (  )  const [inline]

Get the method used for inlier detection.

Definition at line 105 of file pe.h.

void pe::PoseEstimator::matchFrames ( const fc::Frame &  f0,
const fc::Frame &  f1,
std::vector< cv::DMatch > &  fwd_matches 
) [protected]

Definition at line 67 of file pe.cpp.

void pe::PoseEstimator::setMatcher ( const cv::Ptr< cv::DescriptorMatcher > &  matcher  ) 

Set the Descriptor Matcher to use to match features between frames.

Definition at line 113 of file pe.cpp.

void pe::PoseEstimator::setTestMatches ( const std::vector< cv::DMatch > &  matches  )  [inline]

Definition at line 98 of file pe.h.

void pe::PoseEstimator::setTestMode ( bool  mode  ) 

Definition at line 118 of file pe.cpp.


Member Data Documentation

std::vector<cv::DMatch> pe::PoseEstimator::inliers

RANSAC inliers of matches.

Definition at line 58 of file pe.h.

cv::Ptr<cv::DescriptorMatcher> pe::PoseEstimator::matcher

Descriptor matcher to use (features_2d::BruteForceMatcher by default).

Definition at line 67 of file pe.h.

std::vector<cv::DMatch> pe::PoseEstimator::matches

Matches between features in frames.

Definition at line 57 of file pe.h.

Definition at line 78 of file pe.h.

Maximum dist^2 for inliers in pixels.

Definition at line 78 of file pe.h.

Minimum disparity for RANSAC point matches.

Definition at line 75 of file pe.h.

number of RANSAC iterations

Definition at line 61 of file pe.h.

Definition at line 54 of file pe.h.

Eigen::Matrix3d pe::PoseEstimator::rot

Rotation matrix of camera between the frames.

Definition at line 105 of file pe.h.

std::vector<cv::DMatch> pe::PoseEstimator::testMatches [protected]

Definition at line 115 of file pe.h.

bool pe::PoseEstimator::testMode [protected]

Definition at line 114 of file pe.h.

Eigen::Vector3d pe::PoseEstimator::trans

Translation of the camera between the frames.

Definition at line 109 of file pe.h.

Definition at line 51 of file pe.h.

Whether to do windowed or whole-image matching.

Definition at line 64 of file pe.h.

Definition at line 68 of file pe.h.

Definition at line 68 of file pe.h.


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


posest
Author(s): Kurt Konolige
autogenerated on Fri Jan 11 09:14:36 2013