#include <ndt_frame.h>
Public Member Functions | |
| size_t | estimate (const NDTFrame< PointSource > &f0, const NDTFrame< PointTarget > &f1) | 
| size_t | estimate (const NDTFrame< PointSource > &f0, const NDTFrame< PointTarget > &f1, const std::vector< cv::DMatch > &matches) | 
| const std::vector< cv::DMatch > & | getInliers () const | 
| Eigen::Affine3f | getTransform () | 
| void | matchFrames (const NDTFrame< PointSource > &f0, const NDTFrame< PointTarget > &f2, std::vector< cv::DMatch > &fwd_matches) | 
| PoseEstimator (int NRansac, double maxidx, double maxidd) | |
Public Attributes | |
| std::vector< cv::DMatch > | inliers | 
| cv::Ptr< cv::DescriptorMatcher > | matcher | 
| Descriptor matcher to use (features_2d::BruteForceMatcher by default).   | |
| std::vector< cv::DMatch > | matches | 
| Matches between features in frames.   | |
| double | maxDist | 
| double | maxInlierDDist2 | 
| double | maxInlierXDist2 | 
| Maximum dist^2 for inliers in pixels.   | |
| double | minDist | 
| int | numRansac | 
| number of RANSAC iterations   | |
| bool | projectMatches | 
| Eigen::Quaterniond | quat | 
| Eigen::Matrix3d | rot | 
| Rotation matrix of camera between the frames.   | |
| Eigen::Vector3d | trans | 
| Translation of the camera between the frames.   | |
| bool | windowed | 
| Whether to do windowed or whole-image matching.   | |
| int | wx | 
| int | wy | 
Definition at line 347 of file ndt_frame.h.
| ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::PoseEstimator | ( | int | NRansac, | 
| double | maxidx, | ||
| double | maxidd | ||
| ) | 
Definition at line 14 of file ndt_frame.hpp.
| size_t ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::estimate | ( | const NDTFrame< PointSource > & | f0, | 
| const NDTFrame< PointTarget > & | f1 | ||
| ) | 
Definition at line 51 of file ndt_frame.hpp.
| size_t ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::estimate | ( | const NDTFrame< PointSource > & | f0, | 
| const NDTFrame< PointTarget > & | f1, | ||
| const std::vector< cv::DMatch > & | matches | ||
| ) | 
Definition at line 87 of file ndt_frame.hpp.
| const std::vector<cv::DMatch>& ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::getInliers | ( | ) |  const [inline] | 
        
Definition at line 355 of file ndt_frame.h.
| Eigen::Affine3f ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::getTransform | ( | ) |  [inline] | 
        
Definition at line 362 of file ndt_frame.h.
| void ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::matchFrames | ( | const NDTFrame< PointSource > & | f0, | 
| const NDTFrame< PointTarget > & | f2, | ||
| std::vector< cv::DMatch > & | fwd_matches | ||
| ) | 
Definition at line 36 of file ndt_frame.hpp.
| std::vector<cv::DMatch> ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::inliers | 
RANSAC inliers of matches.
Definition at line 371 of file ndt_frame.h.
| cv::Ptr<cv::DescriptorMatcher> ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::matcher | 
Descriptor matcher to use (features_2d::BruteForceMatcher by default).
Definition at line 385 of file ndt_frame.h.
| std::vector<cv::DMatch> ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::matches | 
Matches between features in frames.
Definition at line 370 of file ndt_frame.h.
| double ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::maxDist | 
Definition at line 381 of file ndt_frame.h.
| double ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::maxInlierDDist2 | 
Definition at line 379 of file ndt_frame.h.
| double ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::maxInlierXDist2 | 
Maximum dist^2 for inliers in pixels.
Definition at line 379 of file ndt_frame.h.
| double ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::minDist | 
Definition at line 382 of file ndt_frame.h.
| int ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::numRansac | 
number of RANSAC iterations
Definition at line 373 of file ndt_frame.h.
| bool ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::projectMatches | 
Definition at line 393 of file ndt_frame.h.
| Eigen::Quaterniond ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::quat | 
Definition at line 390 of file ndt_frame.h.
| Eigen::Matrix3d ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::rot | 
Rotation matrix of camera between the frames.
Definition at line 389 of file ndt_frame.h.
| Eigen::Vector3d ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::trans | 
Translation of the camera between the frames.
Definition at line 391 of file ndt_frame.h.
| bool ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::windowed | 
Whether to do windowed or whole-image matching.
Definition at line 376 of file ndt_frame.h.
| int ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::wx | 
Definition at line 386 of file ndt_frame.h.
| int ndt_feature_reg::PoseEstimator< PointSource, PointTarget >::wy | 
Definition at line 386 of file ndt_frame.h.