Detects graph correspondences based on visual feature matching between keyframes. More...
#include <keyframe_graph_detector.h>
Public Types | |
enum | CandidateGenerationMethod { CANDIDATE_GENERATION_BRUTE_FORCE, CANDIDATE_GENERATION_SURF_TREE, CANDIDATE_GENERATION_BRUTE_FORCE, CANDIDATE_GENERATION_SURF_TREE } |
enum | CandidateGenerationMethod { CANDIDATE_GENERATION_BRUTE_FORCE, CANDIDATE_GENERATION_SURF_TREE, CANDIDATE_GENERATION_BRUTE_FORCE, CANDIDATE_GENERATION_SURF_TREE } |
enum | PairwiseMatcherIndex { PAIRWISE_MATCHER_LINEAR, PAIRWISE_MATCHER_KDTREE, PAIRWISE_MATCHER_LINEAR, PAIRWISE_MATCHER_KDTREE } |
enum | PairwiseMatcherIndex { PAIRWISE_MATCHER_LINEAR, PAIRWISE_MATCHER_KDTREE, PAIRWISE_MATCHER_LINEAR, PAIRWISE_MATCHER_KDTREE } |
enum | PairwiseMatchingMethod { PAIRWISE_MATCHING_BFSAC, PAIRWISE_MATCHING_RANSAC, PAIRWISE_MATCHING_BFSAC, PAIRWISE_MATCHING_RANSAC } |
enum | PairwiseMatchingMethod { PAIRWISE_MATCHING_BFSAC, PAIRWISE_MATCHING_RANSAC, PAIRWISE_MATCHING_BFSAC, PAIRWISE_MATCHING_RANSAC } |
Public Member Functions | |
void | buildAssociationMatrix (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildAssociationMatrix (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildAssociationMatrix_Iterative (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildAssociationMatrix_Iterative (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCandidateMatrix (const KeyframeVector &keyframes) |
void | buildCandidateMatrix (const KeyframeVector &keyframes) |
void | buildCandidateMatrixSurfTree () |
Takes in a matrix of matches from a SURF tree (match_matrix_) and marks the top n_candidates in each row into (candidate_matrix) | |
void | buildCandidateMatrixSurfTree () |
void | buildCandidateMatrixSurfTree_Iterative (int v) |
Takes in a matrix of matches from a SURF tree (match_matrix_) and marks the top n_candidates in each row into (candidate_matrix) | |
void | buildCandidateMatrixSurfTree_Iterative (int v) |
void | buildCorrespondenceMatrix (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_mine (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_mine (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_mine_Iterative (u_int kf_idx_q, const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_mine_Iterative (u_int kf_idx_q, const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_onlyLandmarks (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_onlyLandmarks (const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_rgb_Iterative (u_int kf_idx_q, const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildCorrespondenceMatrix_rgb_Iterative (u_int kf_idx_q, const KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | buildMatchMatrixSurfTree (const KeyframeVector &keyframes) |
Builds a matrix of nearest neighbor matches between keyframes using a kdtree. | |
void | buildMatchMatrixSurfTree (const KeyframeVector &keyframes) |
void | buildMatchMatrixSurfTree_Iterative (unsigned int kf_idx, const KeyframeVector &keyframes) |
void | buildMatchMatrixSurfTree_Iterative (unsigned int kf_idx, const KeyframeVector &keyframes) |
void | generateKeyframeAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | generateKeyframeAssociations (KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | generateKeyframeAssociations_Iterative (KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
void | generateKeyframeAssociations_Iterative (KeyframeVector &keyframes, KeyframeAssociationVector &associations) |
const cv::Mat | getAssociationMatrix () const |
const cv::Mat | getAssociationMatrix () const |
void | getCandidateMatches (const RGBDFrame &frame_q, const RGBDFrame &frame_t, cv::FlannBasedMatcher &matcher, DMatchVector &candidate_matches) |
void | getCandidateMatches (const RGBDFrame &frame_q, const RGBDFrame &frame_t, cv::FlannBasedMatcher &matcher, DMatchVector &candidate_matches) |
const cv::Mat | getCandidateMatrix () const |
const cv::Mat | getCandidateMatrix () const |
const cv::Mat | getCorrespondenceMatrix () const |
const cv::Mat | getCorrespondenceMatrix () const |
const std::vector< std::vector < aruco::Marker > > | getMarkers () const |
const std::vector< std::vector < aruco::Marker > > | getMarkers () const |
const cv::Mat | getMatchMatrix () const |
const cv::Mat | getMatchMatrix () const |
KeyframeGraphDetector () | |
Constructor from ROS nodehandles. | |
KeyframeGraphDetector () | |
Constructor from ROS nodehandles. | |
int | pairwiseMatching (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatching (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatchingBFSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatchingBFSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatchingRANSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatchingRANSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation) |
int | pairwiseMatchingRANSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation, std::vector< cv::DMatch > matches) |
int | pairwiseMatchingRANSAC (int kf_idx_q, int kf_idx_t, const KeyframeVector &keyframes, DMatchVector &best_inlier_matches, Eigen::Matrix4f &best_transformation, std::vector< cv::DMatch > matches) |
void | prepareFeaturesForRANSAC (KeyframeVector &keyframes) |
void | prepareFeaturesForRANSAC (KeyframeVector &keyframes) |
void | prepareFeaturesForRANSAC_Iterative (u_int kf_idx, KeyframeVector &keyframes) |
void | prepareFeaturesForRANSAC_Iterative (u_int kf_idx, KeyframeVector &keyframes) |
void | prepareFeaturesForRANSAC_mine (KeyframeVector &keyframes) |
void | prepareFeaturesForRANSAC_mine (KeyframeVector &keyframes) |
void | prepareMatchers (const KeyframeVector &keyframes) |
void | prepareMatchers (const KeyframeVector &keyframes) |
void | setCandidateGenerationMethod (CandidateGenerationMethod candidate_method) |
void | setCandidateGenerationMethod (CandidateGenerationMethod candidate_method) |
void | setKNearestNeighbors (int k_nearest_neighbors) |
void | setKNearestNeighbors (int k_nearest_neighbors) |
void | setMapping (bool mapping) |
void | setMapping (bool mapping) |
void | setMatcherMaxDescDist (double matcher_max_desc_dist) |
void | setMatcherMaxDescDist (double matcher_max_desc_dist) |
void | setMatcherMaxDescRatio (double matcher_max_desc_ratio) |
void | setMatcherMaxDescRatio (double matcher_max_desc_ratio) |
void | setMatcherUseDescRatioTest (bool matcher_use_desc_ratio_test) |
void | setMatcherUseDescRatioTest (bool matcher_use_desc_ratio_test) |
void | setMaxIterations (bool ransac_max_iterations) |
void | setMaxIterations (bool ransac_max_iterations) |
void | setNCandidates (int n_candidates) |
void | setNCandidates (int n_candidates) |
void | setNKeypoints (int n_keypoints) |
void | setNKeypoints (int n_keypoints) |
void | setOutputPath (const std::string &output_path) |
void | setOutputPath (const std::string &output_path) |
void | setPairwiseMatcherIndex (PairwiseMatcherIndex pairwsie_matcher_index) |
void | setPairwiseMatcherIndex (PairwiseMatcherIndex pairwsie_matcher_index) |
void | setPairwiseMatchingMethod (PairwiseMatchingMethod pairwsie_matching_method) |
void | setPairwiseMatchingMethod (PairwiseMatchingMethod pairwsie_matching_method) |
void | setSacMinInliers (int min) |
void | setSacMinInliers (int min) |
void | setSACReestimateTf (bool sac_reestimate_tf) |
void | setSACReestimateTf (bool sac_reestimate_tf) |
void | setSACSaveResults (bool sac_save_results) |
void | setSACSaveResults (bool sac_save_results) |
void | setVerbose (bool verbose) |
void | setVerbose (bool verbose) |
virtual | ~KeyframeGraphDetector () |
Default destructor. | |
virtual | ~KeyframeGraphDetector () |
Default destructor. | |
Public Attributes | |
cv::Mat | association_matrix_ |
CV_8UC1, 1 if associated, 0 otherwise. | |
cv::Mat | candidate_matrix_ |
CV_8UC1, 1 if candidate, 0 otherwise. | |
CandidateGenerationMethod | candidate_method_ |
TREE of BRUTE_FORCE. | |
cv::Mat | correspondence_matrix_ |
CV_16UC1, for tree-based matching, contains number of inlier matches. | |
std::vector< std::vector < aruco::Marker > > | found_markers |
double | init_surf_threshold_ |
int | k_nearest_neighbors_ |
How many nearest neighbors are requested per keypoint. | |
double | log_one_minus_ransac_confidence_ |
bool | mapping_ |
float | marker_size |
cv::Mat | match_matrix_ |
CV_16UC1, for tree-based matching, contains number of total matches. | |
double | matcher_max_desc_dist_ |
Maximum distance (in descriptor space) between two features to be considered a correspondence candidate. | |
double | matcher_max_desc_ratio_ |
bool | matcher_use_desc_ratio_test_ |
std::vector < cv::FlannBasedMatcher > | matchers_ |
double | n_candidates_ |
For kd-tree based correspondences, how many candidate keyframes will be tested agains the query keyframe using a RANSAC test. | |
int | n_keypoints_ |
Number of desired keypoints to detect in each image. | |
int | n_matches_accept |
u_int | n_original_poses |
std::string | output_path_ |
The path where to save images if sac_save_results_ is true. | |
PairwiseMatcherIndex | pairwise_matcher_index_ |
PairwiseMatchingMethod | pairwise_matching_method_ |
double | ransac_confidence_ |
int | ransac_max_iterations_ |
Maximim iterations for the RANSAC test. | |
double | ransac_sufficient_inlier_ratio_ |
double | sac_max_eucl_dist_sq_ |
Maximum distance squared (in Euclidean space) between two features to be considered a correspondence candidate. | |
int | sac_min_inliers_ |
How many inliers are required to pass the RANSAC test. | |
bool | sac_reestimate_tf_ |
bool | sac_save_results_ |
If true, positive RANSAC results will be saved to file as images with keypoint correspondences. | |
bool | verbose_ |
Detects graph correspondences based on visual feature matching between keyframes.
Definition at line 43 of file include/rgbdtools/graph/keyframe_graph_detector.h.
CANDIDATE_GENERATION_BRUTE_FORCE | |
CANDIDATE_GENERATION_SURF_TREE | |
CANDIDATE_GENERATION_BRUTE_FORCE | |
CANDIDATE_GENERATION_SURF_TREE |
Definition at line 47 of file include/rgbdtools/graph/keyframe_graph_detector.h.
CANDIDATE_GENERATION_BRUTE_FORCE | |
CANDIDATE_GENERATION_SURF_TREE | |
CANDIDATE_GENERATION_BRUTE_FORCE | |
CANDIDATE_GENERATION_SURF_TREE |
Definition at line 47 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
PAIRWISE_MATCHER_LINEAR | |
PAIRWISE_MATCHER_KDTREE | |
PAIRWISE_MATCHER_LINEAR | |
PAIRWISE_MATCHER_KDTREE |
Definition at line 59 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
PAIRWISE_MATCHER_LINEAR | |
PAIRWISE_MATCHER_KDTREE | |
PAIRWISE_MATCHER_LINEAR | |
PAIRWISE_MATCHER_KDTREE |
Definition at line 59 of file include/rgbdtools/graph/keyframe_graph_detector.h.
PAIRWISE_MATCHING_BFSAC | |
PAIRWISE_MATCHING_RANSAC | |
PAIRWISE_MATCHING_BFSAC | |
PAIRWISE_MATCHING_RANSAC |
Definition at line 53 of file include/rgbdtools/graph/keyframe_graph_detector.h.
PAIRWISE_MATCHING_BFSAC | |
PAIRWISE_MATCHING_RANSAC | |
PAIRWISE_MATCHING_BFSAC | |
PAIRWISE_MATCHING_RANSAC |
Definition at line 53 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
Constructor from ROS nodehandles.
nh | the public nodehandle |
nh_private | the private nodehandle |
Definition at line 30 of file keyframe_graph_detector.cpp.
rgbdtools::KeyframeGraphDetector::~KeyframeGraphDetector | ( | ) | [virtual] |
Default destructor.
Definition at line 76 of file keyframe_graph_detector.cpp.
Constructor from ROS nodehandles.
nh | the public nodehandle |
nh_private | the private nodehandle |
virtual rgbdtools::KeyframeGraphDetector::~KeyframeGraphDetector | ( | ) | [virtual] |
Default destructor.
void rgbdtools::KeyframeGraphDetector::buildAssociationMatrix | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 385 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildAssociationMatrix | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildAssociationMatrix_Iterative | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildAssociationMatrix_Iterative | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 399 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCandidateMatrix | ( | const KeyframeVector & | keyframes | ) |
void rgbdtools::KeyframeGraphDetector::buildCandidateMatrix | ( | const KeyframeVector & | keyframes | ) |
Definition at line 409 of file keyframe_graph_detector.cpp.
Takes in a matrix of matches from a SURF tree (match_matrix_) and marks the top n_candidates in each row into (candidate_matrix)
Definition at line 605 of file keyframe_graph_detector.cpp.
Takes in a matrix of matches from a SURF tree (match_matrix_) and marks the top n_candidates in each row into (candidate_matrix)
Definition at line 559 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 644 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_mine | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 820 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_mine | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_mine_Iterative | ( | u_int | kf_idx_q, |
const KeyframeVector & | keyframes, | ||
KeyframeAssociationVector & | associations | ||
) |
Definition at line 1313 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_mine_Iterative | ( | u_int | kf_idx_q, |
const KeyframeVector & | keyframes, | ||
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_onlyLandmarks | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 731 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_onlyLandmarks | ( | const KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_rgb_Iterative | ( | u_int | kf_idx_q, |
const KeyframeVector & | keyframes, | ||
KeyframeAssociationVector & | associations | ||
) |
Definition at line 1129 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildCorrespondenceMatrix_rgb_Iterative | ( | u_int | kf_idx_q, |
const KeyframeVector & | keyframes, | ||
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::buildMatchMatrixSurfTree | ( | const KeyframeVector & | keyframes | ) |
void rgbdtools::KeyframeGraphDetector::buildMatchMatrixSurfTree | ( | const KeyframeVector & | keyframes | ) |
Builds a matrix of nearest neighbor matches between keyframes using a kdtree.
match_matrix[query, train] = X correspondences
Definition at line 506 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::buildMatchMatrixSurfTree_Iterative | ( | unsigned int | kf_idx, |
const KeyframeVector & | keyframes | ||
) |
void rgbdtools::KeyframeGraphDetector::buildMatchMatrixSurfTree_Iterative | ( | unsigned int | kf_idx, |
const KeyframeVector & | keyframes | ||
) |
Definition at line 433 of file keyframe_graph_detector.cpp.
void rgbdtools::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 |
void rgbdtools::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 173 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::generateKeyframeAssociations_Iterative | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
void rgbdtools::KeyframeGraphDetector::generateKeyframeAssociations_Iterative | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) |
Definition at line 183 of file keyframe_graph_detector.cpp.
const cv::Mat rgbdtools::KeyframeGraphDetector::getAssociationMatrix | ( | ) | const [inline] |
Definition at line 92 of file include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getAssociationMatrix | ( | ) | const [inline] |
Definition at line 92 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
void rgbdtools::KeyframeGraphDetector::getCandidateMatches | ( | const RGBDFrame & | frame_q, |
const RGBDFrame & | frame_t, | ||
cv::FlannBasedMatcher & | matcher, | ||
DMatchVector & | candidate_matches | ||
) |
Definition at line 1414 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::getCandidateMatches | ( | const RGBDFrame & | frame_q, |
const RGBDFrame & | frame_t, | ||
cv::FlannBasedMatcher & | matcher, | ||
DMatchVector & | candidate_matches | ||
) |
const cv::Mat rgbdtools::KeyframeGraphDetector::getCandidateMatrix | ( | ) | const [inline] |
Definition at line 93 of file include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getCandidateMatrix | ( | ) | const [inline] |
Definition at line 93 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getCorrespondenceMatrix | ( | ) | const [inline] |
Definition at line 94 of file include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getCorrespondenceMatrix | ( | ) | const [inline] |
Definition at line 94 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
const std::vector<std::vector<aruco::Marker> > rgbdtools::KeyframeGraphDetector::getMarkers | ( | ) | const [inline] |
Definition at line 96 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
const std::vector<std::vector<aruco::Marker> > rgbdtools::KeyframeGraphDetector::getMarkers | ( | ) | const [inline] |
Definition at line 96 of file include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getMatchMatrix | ( | ) | const [inline] |
Definition at line 95 of file rgbdtools_git/include/rgbdtools/graph/keyframe_graph_detector.h.
const cv::Mat rgbdtools::KeyframeGraphDetector::getMatchMatrix | ( | ) | const [inline] |
Definition at line 95 of file include/rgbdtools/graph/keyframe_graph_detector.h.
int rgbdtools::KeyframeGraphDetector::pairwiseMatching | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
int rgbdtools::KeyframeGraphDetector::pairwiseMatching | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
Definition at line 1473 of file keyframe_graph_detector.cpp.
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingBFSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
Definition at line 1496 of file keyframe_graph_detector.cpp.
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingBFSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingRANSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
Definition at line 1614 of file keyframe_graph_detector.cpp.
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingRANSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation | ||
) |
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingRANSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation, | ||
std::vector< cv::DMatch > | matches | ||
) |
Definition at line 1756 of file keyframe_graph_detector.cpp.
int rgbdtools::KeyframeGraphDetector::pairwiseMatchingRANSAC | ( | int | kf_idx_q, |
int | kf_idx_t, | ||
const KeyframeVector & | keyframes, | ||
DMatchVector & | best_inlier_matches, | ||
Eigen::Matrix4f & | best_transformation, | ||
std::vector< cv::DMatch > | matches | ||
) |
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC | ( | KeyframeVector & | keyframes | ) |
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC | ( | KeyframeVector & | keyframes | ) |
Definition at line 276 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC_Iterative | ( | u_int | kf_idx, |
KeyframeVector & | keyframes | ||
) |
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC_Iterative | ( | u_int | kf_idx, |
KeyframeVector & | keyframes | ||
) |
Definition at line 230 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC_mine | ( | KeyframeVector & | keyframes | ) |
void rgbdtools::KeyframeGraphDetector::prepareFeaturesForRANSAC_mine | ( | KeyframeVector & | keyframes | ) |
Definition at line 340 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::prepareMatchers | ( | const KeyframeVector & | keyframes | ) |
Definition at line 198 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::prepareMatchers | ( | const KeyframeVector & | keyframes | ) |
void rgbdtools::KeyframeGraphDetector::setCandidateGenerationMethod | ( | CandidateGenerationMethod | candidate_method | ) |
Definition at line 146 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setCandidateGenerationMethod | ( | CandidateGenerationMethod | candidate_method | ) |
void rgbdtools::KeyframeGraphDetector::setKNearestNeighbors | ( | int | k_nearest_neighbors | ) |
Definition at line 120 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setKNearestNeighbors | ( | int | k_nearest_neighbors | ) |
void rgbdtools::KeyframeGraphDetector::setMapping | ( | bool | mapping | ) |
Definition at line 80 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setMapping | ( | bool | mapping | ) |
void rgbdtools::KeyframeGraphDetector::setMatcherMaxDescDist | ( | double | matcher_max_desc_dist | ) |
Definition at line 110 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setMatcherMaxDescDist | ( | double | matcher_max_desc_dist | ) |
void rgbdtools::KeyframeGraphDetector::setMatcherMaxDescRatio | ( | double | matcher_max_desc_ratio | ) |
void rgbdtools::KeyframeGraphDetector::setMatcherMaxDescRatio | ( | double | matcher_max_desc_ratio | ) |
Definition at line 105 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setMatcherUseDescRatioTest | ( | bool | matcher_use_desc_ratio_test | ) |
Definition at line 100 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setMatcherUseDescRatioTest | ( | bool | matcher_use_desc_ratio_test | ) |
void rgbdtools::KeyframeGraphDetector::setMaxIterations | ( | bool | ransac_max_iterations | ) |
void rgbdtools::KeyframeGraphDetector::setMaxIterations | ( | bool | ransac_max_iterations | ) |
Definition at line 84 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setNCandidates | ( | int | n_candidates | ) |
void rgbdtools::KeyframeGraphDetector::setNCandidates | ( | int | n_candidates | ) |
Definition at line 115 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setNKeypoints | ( | int | n_keypoints | ) |
Definition at line 125 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setNKeypoints | ( | int | n_keypoints | ) |
void rgbdtools::KeyframeGraphDetector::setOutputPath | ( | const std::string & | output_path | ) |
Definition at line 130 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setOutputPath | ( | const std::string & | output_path | ) |
void rgbdtools::KeyframeGraphDetector::setPairwiseMatcherIndex | ( | PairwiseMatcherIndex | pairwsie_matcher_index | ) |
void rgbdtools::KeyframeGraphDetector::setPairwiseMatcherIndex | ( | PairwiseMatcherIndex | pairwsie_matcher_index | ) |
Definition at line 164 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setPairwiseMatchingMethod | ( | PairwiseMatchingMethod | pairwsie_matching_method | ) |
Definition at line 155 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setPairwiseMatchingMethod | ( | PairwiseMatchingMethod | pairwsie_matching_method | ) |
void rgbdtools::KeyframeGraphDetector::setSacMinInliers | ( | int | min | ) |
Definition at line 89 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setSacMinInliers | ( | int | min | ) |
void rgbdtools::KeyframeGraphDetector::setSACReestimateTf | ( | bool | sac_reestimate_tf | ) |
void rgbdtools::KeyframeGraphDetector::setSACReestimateTf | ( | bool | sac_reestimate_tf | ) |
Definition at line 95 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setSACSaveResults | ( | bool | sac_save_results | ) |
Definition at line 136 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setSACSaveResults | ( | bool | sac_save_results | ) |
void rgbdtools::KeyframeGraphDetector::setVerbose | ( | bool | verbose | ) |
Definition at line 141 of file keyframe_graph_detector.cpp.
void rgbdtools::KeyframeGraphDetector::setVerbose | ( | bool | verbose | ) |
CV_8UC1, 1 if associated, 0 otherwise.
Definition at line 198 of file include/rgbdtools/graph/keyframe_graph_detector.h.
CV_8UC1, 1 if candidate, 0 otherwise.
Definition at line 201 of file include/rgbdtools/graph/keyframe_graph_detector.h.
TREE of BRUTE_FORCE.
Definition at line 184 of file include/rgbdtools/graph/keyframe_graph_detector.h.
CV_16UC1, for tree-based matching, contains number of inlier matches.
Definition at line 204 of file include/rgbdtools/graph/keyframe_graph_detector.h.
std::vector< std::vector< aruco::Marker > > rgbdtools::KeyframeGraphDetector::found_markers |
Definition at line 192 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 179 of file include/rgbdtools/graph/keyframe_graph_detector.h.
How many nearest neighbors are requested per keypoint.
Definition at line 173 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 155 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 124 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 191 of file include/rgbdtools/graph/keyframe_graph_detector.h.
CV_16UC1, for tree-based matching, contains number of total matches.
Definition at line 207 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Maximum distance (in descriptor space) between two features to be considered a correspondence candidate.
Definition at line 143 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 138 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 136 of file include/rgbdtools/graph/keyframe_graph_detector.h.
std::vector< cv::FlannBasedMatcher > rgbdtools::KeyframeGraphDetector::matchers_ |
Definition at line 209 of file include/rgbdtools/graph/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 169 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Number of desired keypoints to detect in each image.
Definition at line 177 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 181 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 194 of file include/rgbdtools/graph/keyframe_graph_detector.h.
std::string rgbdtools::KeyframeGraphDetector::output_path_ |
The path where to save images if sac_save_results_ is true.
Definition at line 164 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 188 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 186 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 154 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Maximim iterations for the RANSAC test.
Definition at line 127 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 152 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Maximum distance squared (in Euclidean space) between two features to be considered a correspondence candidate.
Definition at line 148 of file include/rgbdtools/graph/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 134 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 150 of file include/rgbdtools/graph/keyframe_graph_detector.h.
If true, positive RANSAC results will be saved to file as images with keypoint correspondences.
Definition at line 160 of file include/rgbdtools/graph/keyframe_graph_detector.h.
Definition at line 123 of file include/rgbdtools/graph/keyframe_graph_detector.h.