All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends
Public Member Functions | Private Member Functions | Private Attributes
rgbdtools::MotionEstimationPairwiseRANSAC Class Reference

Motion estimation based on aligning sparse features against a persistent, dynamic model. More...

#include <motion_estimation_pairwise_ransac.h>

Inheritance diagram for rgbdtools::MotionEstimationPairwiseRANSAC:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)
 Main method for estimating the motion given an RGBD frame.
bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)
 Main method for estimating the motion given an RGBD frame.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MotionEstimationPairwiseRANSAC ()
 Constructor from ROS noehandles.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MotionEstimationPairwiseRANSAC ()
 Constructor from ROS noehandles.
void setFeatureDetector (FeatureDetectorPtr detector)
void setFeatureDetector (FeatureDetectorPtr detector)
virtual ~MotionEstimationPairwiseRANSAC ()
 Default destructor.
virtual ~MotionEstimationPairwiseRANSAC ()
 Default destructor.

Private Member Functions

double distEuclideanSq (const PointFeature &a, const PointFeature &b)
double distEuclideanSq (const PointFeature &a, const PointFeature &b)
void get3RandomIndices (int n, std::set< int > &mask, IntVector &output)
void get3RandomIndices (int n, std::set< int > &mask, IntVector &output)
void getCandidateMatches (const RGBDFrame &frame_q, const RGBDFrame &frame_t, cv::DescriptorMatcher &matcher, DMatchVector &candidate_matches)
void getCandidateMatches (const RGBDFrame &frame_q, const RGBDFrame &frame_t, cv::DescriptorMatcher &matcher, DMatchVector &candidate_matches)
void getRandomIndices (int k, int n, IntVector &output)
void getRandomIndices (int k, int n, IntVector &output)
int pairwiseMatchingRANSAC (const RGBDFrame &frame_q, const RGBDFrame &frame_t, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation)
int pairwiseMatchingRANSAC (const RGBDFrame &frame_q, const RGBDFrame &frame_t, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation)

Private Attributes

FeatureDetectorPtr detector_
AffineTransform f2b_
 Transform from fixed to moving frame.
bool initialized_
double log_one_minus_ransac_confidence_
double matcher_max_desc_dist_
double matcher_max_desc_ratio_
bool matcher_use_desc_ratio_test_
RGBDFrameprev_frame_
double ransac_confidence_
int ransac_max_iterations_
double sac_max_eucl_dist_sq_
int sac_min_inliers_
bool sac_reestimate_tf_

Detailed Description

Motion estimation based on aligning sparse features against a persistent, dynamic model.

The model is build from incoming features through a Kalman Filter update step.

Definition at line 43 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.


Constructor & Destructor Documentation

Constructor from ROS noehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private notehandle

Definition at line 28 of file motion_estimation_pairwise_ransac.cpp.

Default destructor.

Definition at line 57 of file motion_estimation_pairwise_ransac.cpp.

Constructor from ROS noehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private notehandle

Default destructor.


Member Function Documentation

double rgbdtools::MotionEstimationPairwiseRANSAC::distEuclideanSq ( const PointFeature a,
const PointFeature b 
) [inline, private]
double rgbdtools::MotionEstimationPairwiseRANSAC::distEuclideanSq ( const PointFeature a,
const PointFeature b 
) [inline, private]
void rgbdtools::MotionEstimationPairwiseRANSAC::get3RandomIndices ( int  n,
std::set< int > &  mask,
IntVector output 
) [inline, private]
void rgbdtools::MotionEstimationPairwiseRANSAC::get3RandomIndices ( int  n,
std::set< int > &  mask,
IntVector output 
) [inline, private]
void rgbdtools::MotionEstimationPairwiseRANSAC::getCandidateMatches ( const RGBDFrame frame_q,
const RGBDFrame frame_t,
cv::DescriptorMatcher &  matcher,
DMatchVector candidate_matches 
) [private]
void rgbdtools::MotionEstimationPairwiseRANSAC::getCandidateMatches ( const RGBDFrame frame_q,
const RGBDFrame frame_t,
cv::DescriptorMatcher &  matcher,
DMatchVector candidate_matches 
) [private]

Definition at line 268 of file motion_estimation_pairwise_ransac.cpp.

bool rgbdtools::MotionEstimationPairwiseRANSAC::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [virtual]

Main method for estimating the motion given an RGBD frame.

Parameters:
framethe current RGBD frame
predictionthe predicted motion (currently ignored)
motionthe (output) incremental motion, wrt the fixed frame
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Implements rgbdtools::MotionEstimation.

bool rgbdtools::MotionEstimationPairwiseRANSAC::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [virtual]

Main method for estimating the motion given an RGBD frame.

Parameters:
framethe current RGBD frame
predictionthe predicted motion (currently ignored)
motionthe (output) incremental motion, wrt the fixed frame
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Implements rgbdtools::MotionEstimation.

Definition at line 62 of file motion_estimation_pairwise_ransac.cpp.

void rgbdtools::MotionEstimationPairwiseRANSAC::getRandomIndices ( int  k,
int  n,
IntVector output 
) [inline, private]
void rgbdtools::MotionEstimationPairwiseRANSAC::getRandomIndices ( int  k,
int  n,
IntVector output 
) [inline, private]
int rgbdtools::MotionEstimationPairwiseRANSAC::pairwiseMatchingRANSAC ( const RGBDFrame frame_q,
const RGBDFrame frame_t,
DMatchVector best_inlier_matches,
Eigen::Matrix4f &  best_transformation 
) [private]
int rgbdtools::MotionEstimationPairwiseRANSAC::pairwiseMatchingRANSAC ( const RGBDFrame frame_q,
const RGBDFrame frame_t,
DMatchVector best_inlier_matches,
Eigen::Matrix4f &  best_transformation 
) [private]

Definition at line 111 of file motion_estimation_pairwise_ransac.cpp.


Member Data Documentation

Transform from fixed to moving frame.

Definition at line 81 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.


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


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:55