Motion estimation based on aligning sparse features against a persistent, dynamic model. More...
#include <motion_estimation_pairwise_ransac.h>

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_ |
| RGBDFrame * | prev_frame_ |
| double | ransac_confidence_ |
| int | ransac_max_iterations_ |
| double | sac_max_eucl_dist_sq_ |
| int | sac_min_inliers_ |
| bool | sac_reestimate_tf_ |
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 from ROS noehandles.
| nh | the public nodehandle |
| nh_private | the 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.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW rgbdtools::MotionEstimationPairwiseRANSAC::MotionEstimationPairwiseRANSAC | ( | ) |
Constructor from ROS noehandles.
| nh | the public nodehandle |
| nh_private | the private notehandle |
| virtual rgbdtools::MotionEstimationPairwiseRANSAC::~MotionEstimationPairwiseRANSAC | ( | ) | [virtual] |
Default destructor.
| double rgbdtools::MotionEstimationPairwiseRANSAC::distEuclideanSq | ( | const PointFeature & | a, |
| const PointFeature & | b | ||
| ) | [inline, private] |
Definition at line 150 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| double rgbdtools::MotionEstimationPairwiseRANSAC::distEuclideanSq | ( | const PointFeature & | a, |
| const PointFeature & | b | ||
| ) | [inline, private] |
Definition at line 150 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| void rgbdtools::MotionEstimationPairwiseRANSAC::get3RandomIndices | ( | int | n, |
| std::set< int > & | mask, | ||
| IntVector & | output | ||
| ) | [inline, private] |
Definition at line 127 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| void rgbdtools::MotionEstimationPairwiseRANSAC::get3RandomIndices | ( | int | n, |
| std::set< int > & | mask, | ||
| IntVector & | output | ||
| ) | [inline, private] |
Definition at line 127 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| 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.
| frame | the current RGBD frame |
| prediction | the predicted motion (currently ignored) |
| motion | the (output) incremental motion, wrt the fixed frame |
| true | the motion estimation was successful |
| false | the 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.
| frame | the current RGBD frame |
| prediction | the predicted motion (currently ignored) |
| motion | the (output) incremental motion, wrt the fixed frame |
| true | the motion estimation was successful |
| false | the 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] |
Definition at line 105 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| void rgbdtools::MotionEstimationPairwiseRANSAC::getRandomIndices | ( | int | k, |
| int | n, | ||
| IntVector & | output | ||
| ) | [inline, private] |
Definition at line 105 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| 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.
| void rgbdtools::MotionEstimationPairwiseRANSAC::setFeatureDetector | ( | FeatureDetectorPtr | detector | ) | [inline] |
Definition at line 71 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
| void rgbdtools::MotionEstimationPairwiseRANSAC::setFeatureDetector | ( | FeatureDetectorPtr | detector | ) | [inline] |
Definition at line 71 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 79 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Transform from fixed to moving frame.
Definition at line 81 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
bool rgbdtools::MotionEstimationPairwiseRANSAC::initialized_ [private] |
Definition at line 75 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 90 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
double rgbdtools::MotionEstimationPairwiseRANSAC::matcher_max_desc_dist_ [private] |
Definition at line 93 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
double rgbdtools::MotionEstimationPairwiseRANSAC::matcher_max_desc_ratio_ [private] |
Definition at line 92 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 91 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 77 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
double rgbdtools::MotionEstimationPairwiseRANSAC::ransac_confidence_ [private] |
Definition at line 89 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 88 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
double rgbdtools::MotionEstimationPairwiseRANSAC::sac_max_eucl_dist_sq_ [private] |
Definition at line 86 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 85 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.
Definition at line 87 of file include/rgbdtools/registration/motion_estimation_pairwise_ransac.h.