Detects graph correspondences based on visual feature matching between keyframes. More...
#include <keyframe_graph_detector.h>
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. |
Detects graph correspondences based on visual feature matching between keyframes.
Definition at line 41 of file keyframe_graph_detector.h.
ccny_rgbd::KeyframeGraphDetector::KeyframeGraphDetector | ( | const ros::NodeHandle & | nh, |
const ros::NodeHandle & | nh_private | ||
) |
Constructor from ROS nodehandles.
nh | the public nodehandle |
nh_private | the private nodehandle |
Definition at line 28 of file keyframe_graph_detector.cpp.
ccny_rgbd::KeyframeGraphDetector::~KeyframeGraphDetector | ( | ) | [virtual] |
Default destructor.
Definition at line 60 of file keyframe_graph_detector.cpp.
double ccny_rgbd::KeyframeGraphDetector::distEuclideanSq | ( | const PointFeature & | a, |
const PointFeature & | b | ||
) | [inline, private] |
Squared Euclidean distance between two features in 3D.
a | the first 3D point |
b | the second 3D point |
Definition at line 172 of file keyframe_graph_detector.h.
void ccny_rgbd::KeyframeGraphDetector::generateKeyframeAssociations | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Main method for generating associatuions
keyframes | the input vector of RGBD keyframes |
associations | reference 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)
k | the number of random samples |
n | the (exclusive) upper limit of the number range |
output | the output vector of random numbers |
Definition at line 502 of file keyframe_graph_detector.cpp.
void ccny_rgbd::KeyframeGraphDetector::manualBruteForceAssociations | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) | [private] |
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.
keyframes | the input vector of RGBD keyframes |
associations | reference 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.
frame_a | the first RGBD frame |
frame_b | the second RGBD frame |
max_eucl_dist_sq | maximum 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_dist | maximum descriptor distance between two features in a correspondence for that correspondence to be considered an inlier in the transformation model |
sufficient_inlier_ratio | if the ratio between inlier matches to candidate matches exceeds this, the RANSAC test terminates successfuly |
all_matches | output vector of all the matches |
best_inlier_matches | output vectors of the matches which are inliers to the best transformation model |
best_transformation | the best transformation determined by RANSAC |
Definition at line 217 of file keyframe_graph_detector.cpp.
void ccny_rgbd::KeyframeGraphDetector::prepareFeaturesForRANSAC | ( | KeyframeVector & | keyframes | ) | [private] |
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
keyframes | the 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.
keyframes | the input keyframes |
matcher | the reference to the matcher |
Definition at line 357 of file keyframe_graph_detector.cpp.
void ccny_rgbd::KeyframeGraphDetector::treeAssociations | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) | [private] |
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.
keyframes | the input vector of RGBD keyframes |
associations | reference to the output vector of associations |
Definition at line 375 of file keyframe_graph_detector.cpp.
void ccny_rgbd::KeyframeGraphDetector::visualOdometryAssociations | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) | [private] |
Creates associations based on the visual odometry poses of the frames, ie, associations between consecutive frames only.
keyframes | the input vector of RGBD keyframes |
associations | reference to the output vector of associations |
Definition at line 123 of file keyframe_graph_detector.cpp.
int ccny_rgbd::KeyframeGraphDetector::k_nearest_neighbors_ [private] |
How many nearest neighbors are requested per keypoint.
Definition at line 91 of file keyframe_graph_detector.h.
double ccny_rgbd::KeyframeGraphDetector::max_corresp_dist_desc_ [private] |
Maximum distance (in descriptor space) between two features to be considered a correspondence candidate.
Definition at line 103 of file keyframe_graph_detector.h.
double ccny_rgbd::KeyframeGraphDetector::max_corresp_dist_eucl_ [private] |
Maximum distance (in Euclidean space) between two features to be considered a correspondence candidate.
Definition at line 108 of file keyframe_graph_detector.h.
double ccny_rgbd::KeyframeGraphDetector::max_corresp_dist_eucl_sq_ [private] |
Derived from max_corresp_dist_eucl_.
Definition at line 112 of file keyframe_graph_detector.h.
int ccny_rgbd::KeyframeGraphDetector::max_ransac_iterations_ [private] |
Maximim iterations for the RANSAC test.
Definition at line 73 of file keyframe_graph_detector.h.
int ccny_rgbd::KeyframeGraphDetector::min_ransac_inliers_ [private] |
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.
int ccny_rgbd::KeyframeGraphDetector::n_keypoints_ [private] |
Number of desired keypoints to detect in each image.
Definition at line 116 of file keyframe_graph_detector.h.
double ccny_rgbd::KeyframeGraphDetector::n_ransac_candidates_ [private] |
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.
ros::NodeHandle ccny_rgbd::KeyframeGraphDetector::nh_ [protected] |
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.
std::string ccny_rgbd::KeyframeGraphDetector::ransac_results_path_ [private] |
The path where to save images if save_ransac_results_ is true.
Definition at line 82 of file keyframe_graph_detector.h.
bool ccny_rgbd::KeyframeGraphDetector::save_ransac_results_ [private] |
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.