All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends
Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
ccny_rgbd::KeyframeGraphDetector Class Reference

Detects graph correspondences based on visual feature matching between keyframes. More...

#include <keyframe_graph_detector.h>

List of all members.

Public Member Functions

void generateKeyframeAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations)
 KeyframeGraphDetector (const ros::NodeHandle &nh, const ros::NodeHandle &nh_private)
 Constructor from ROS nodehandles.
virtual ~KeyframeGraphDetector ()
 Default destructor.

Protected Attributes

ros::NodeHandle nh_
 the public nodehandle
ros::NodeHandle nh_private_
 the private nodehandle

Private Member Functions

double distEuclideanSq (const PointFeature &a, const PointFeature &b)
 Squared Euclidean distance between two features in 3D.
void getRandomIndices (int k, int n, IntVector &output)
 Returns k distinct random numbers from 0 to (n-1)
void manualBruteForceAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations)
 Creates associations based on visual matching between keyframes through a RANSAC test (for manually added frames)
void pairwiseMatchingRANSAC (RGBDFrame &frame_a, RGBDFrame &frame_b, double max_eucl_dist_sq, double max_desc_dist, double sufficient_inlier_ratio, std::vector< cv::DMatch > &all_matches, std::vector< cv::DMatch > &best_inlier_matches, Eigen::Matrix4f &best_transformation)
 Given two keyframes, finds all keypoint correposndences which follow a rigid transformation model.
void prepareFeaturesForRANSAC (KeyframeVector &keyframes)
 Goes through all the keyframes and fills out the required information (features, distributinos, etc) which will be needed by RANSAC matching.
void trainMatcher (const KeyframeVector &keyframes, cv::FlannBasedMatcher &matcher)
 Aggregates all features across all keyframes and trains a knn flann matcher in descriptor space.
void treeAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations)
 Creates associations based on visual matching between keyframes through a RANSAC test.
void visualOdometryAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations)
 Creates associations based on the visual odometry poses of the frames, ie, associations between consecutive frames only.

Private Attributes

int k_nearest_neighbors_
 How many nearest neighbors are requested per keypoint.
double max_corresp_dist_desc_
 Maximum distance (in descriptor space) between two features to be considered a correspondence candidate.
double max_corresp_dist_eucl_
 Maximum distance (in Euclidean space) between two features to be considered a correspondence candidate.
double max_corresp_dist_eucl_sq_
 Derived from max_corresp_dist_eucl_.
int max_ransac_iterations_
 Maximim iterations for the RANSAC test.
int min_ransac_inliers_
 How many inliers are required to pass the RANSAC test.
int n_keypoints_
 Number of desired keypoints to detect in each image.
double n_ransac_candidates_
 For kd-tree based correspondences, how many candidate keyframes will be tested agains the query keyframe using a RANSAC test.
std::string ransac_results_path_
 The path where to save images if save_ransac_results_ is true.
bool save_ransac_results_
 If true, positive RANSAC results will be saved to file as images with keypoint correspondences.

Detailed Description

Detects graph correspondences based on visual feature matching between keyframes.

Definition at line 41 of file keyframe_graph_detector.h.


Constructor & Destructor Documentation

Constructor from ROS nodehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private nodehandle

Definition at line 28 of file keyframe_graph_detector.cpp.

Default destructor.

Definition at line 60 of file keyframe_graph_detector.cpp.


Member Function Documentation

double ccny_rgbd::KeyframeGraphDetector::distEuclideanSq ( const PointFeature a,
const PointFeature b 
) [inline, private]

Squared Euclidean distance between two features in 3D.

Parameters:
athe first 3D point
bthe second 3D point
Returns:
squared Euclidean distance between two a and b

Definition at line 172 of file keyframe_graph_detector.h.

Main method for generating associatuions

Parameters:
keyframesthe input vector of RGBD keyframes
associationsreference to the output vector of associations

Definition at line 65 of file keyframe_graph_detector.cpp.

void ccny_rgbd::KeyframeGraphDetector::getRandomIndices ( int  k,
int  n,
IntVector output 
) [private]

Returns k distinct random numbers from 0 to (n-1)

Parameters:
kthe number of random samples
nthe (exclusive) upper limit of the number range
outputthe output vector of random numbers

Definition at line 502 of file keyframe_graph_detector.cpp.

Creates associations based on visual matching between keyframes through a RANSAC test (for manually added frames)

Performs a brute force (each-to-each) matching between all frames which have been manually added.

Parameters:
keyframesthe input vector of RGBD keyframes
associationsreference to the output vector of associations

Definition at line 148 of file keyframe_graph_detector.cpp.

void ccny_rgbd::KeyframeGraphDetector::pairwiseMatchingRANSAC ( RGBDFrame frame_a,
RGBDFrame frame_b,
double  max_eucl_dist_sq,
double  max_desc_dist,
double  sufficient_inlier_ratio,
std::vector< cv::DMatch > &  all_matches,
std::vector< cv::DMatch > &  best_inlier_matches,
Eigen::Matrix4f &  best_transformation 
) [private]

Given two keyframes, finds all keypoint correposndences which follow a rigid transformation model.

Parameters:
frame_athe first RGBD frame
frame_bthe second RGBD frame
max_eucl_dist_sqmaximum squared Euclidean distance (in meters) between two features in a correspondence for that correspondence to be considered an inlier in the transformation model
max_desc_distmaximum descriptor distance between two features in a correspondence for that correspondence to be considered an inlier in the transformation model
sufficient_inlier_ratioif the ratio between inlier matches to candidate matches exceeds this, the RANSAC test terminates successfuly
all_matchesoutput vector of all the matches
best_inlier_matchesoutput vectors of the matches which are inliers to the best transformation model
best_transformationthe best transformation determined by RANSAC

Definition at line 217 of file keyframe_graph_detector.cpp.

Goes through all the keyframes and fills out the required information (features, distributinos, etc) which will be needed by RANSAC matching.

Uses SURF features with an adaptive thershold to ensure a minimum number of feautres (n_keypoints_) detected in each frame

Parameters:
keyframesthe vector of keyframes to be used for associations

Definition at line 78 of file keyframe_graph_detector.cpp.

void ccny_rgbd::KeyframeGraphDetector::trainMatcher ( const KeyframeVector keyframes,
cv::FlannBasedMatcher &  matcher 
) [private]

Aggregates all features across all keyframes and trains a knn flann matcher in descriptor space.

Parameters:
keyframesthe input keyframes
matcherthe reference to the matcher

Definition at line 357 of file keyframe_graph_detector.cpp.

Creates associations based on visual matching between keyframes through a RANSAC test.

Candidates for RANSAC testing are determined by building a kd-tree of all the features (across all keyframe). Then for each keyframe, the tree is used to determine a number of possible candidate keyframes. RANSAC is performed between the query frame and the valid candidates.

Parameters:
keyframesthe input vector of RGBD keyframes
associationsreference to the output vector of associations

Definition at line 375 of file keyframe_graph_detector.cpp.

Creates associations based on the visual odometry poses of the frames, ie, associations between consecutive frames only.

Parameters:
keyframesthe input vector of RGBD keyframes
associationsreference to the output vector of associations

Definition at line 123 of file keyframe_graph_detector.cpp.


Member Data Documentation

How many nearest neighbors are requested per keypoint.

Definition at line 91 of file keyframe_graph_detector.h.

Maximum distance (in descriptor space) between two features to be considered a correspondence candidate.

Definition at line 103 of file keyframe_graph_detector.h.

Maximum distance (in Euclidean space) between two features to be considered a correspondence candidate.

Definition at line 108 of file keyframe_graph_detector.h.

Derived from max_corresp_dist_eucl_.

Definition at line 112 of file keyframe_graph_detector.h.

Maximim iterations for the RANSAC test.

Definition at line 73 of file keyframe_graph_detector.h.

How many inliers are required to pass the RANSAC test.

If a candidate keyframe has fewer correspondences or more, it will not be eligible for a RANSAC test

Definition at line 98 of file keyframe_graph_detector.h.

Number of desired keypoints to detect in each image.

Definition at line 116 of file keyframe_graph_detector.h.

For kd-tree based correspondences, how many candidate keyframes will be tested agains the query keyframe using a RANSAC test.

Definition at line 87 of file keyframe_graph_detector.h.

the public nodehandle

Definition at line 66 of file keyframe_graph_detector.h.

the private nodehandle

Definition at line 67 of file keyframe_graph_detector.h.

The path where to save images if save_ransac_results_ is true.

Definition at line 82 of file keyframe_graph_detector.h.

If true, positive RANSAC results will be saved to file as images with keypoint correspondences.

Definition at line 78 of file keyframe_graph_detector.h.


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


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Fri Apr 12 2013 20:38:48