#include <ndt_frame.h>
Public Member Functions | |
size_t | estimate (const NDTFrame &f0, const NDTFrame &f1) |
size_t | estimate (const NDTFrame &f0, const NDTFrame &f1, const std::vector< cv::DMatch > &matches) |
const std::vector< cv::DMatch > & | getInliers () const |
Eigen::Affine3f | getTransform () |
void | matchFrames (const NDTFrame &f0, const NDTFrame &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 345 of file ndt_frame.h.
ndt_feature_reg::PoseEstimator::PoseEstimator | ( | int | NRansac, |
double | maxidx, | ||
double | maxidd | ||
) |
Definition at line 14 of file ndt_frame.hpp.
size_t ndt_feature_reg::PoseEstimator::estimate | ( | const NDTFrame & | f0, |
const NDTFrame & | f1 | ||
) |
Definition at line 49 of file ndt_frame.cpp.
size_t ndt_feature_reg::PoseEstimator::estimate | ( | const NDTFrame & | f0, |
const NDTFrame & | f1, | ||
const std::vector< cv::DMatch > & | matches | ||
) |
Definition at line 84 of file ndt_frame.cpp.
const std::vector<cv::DMatch>& ndt_feature_reg::PoseEstimator::getInliers | ( | ) | const [inline] |
Definition at line 353 of file ndt_frame.h.
Eigen::Affine3f ndt_feature_reg::PoseEstimator::getTransform | ( | ) | [inline] |
Definition at line 360 of file ndt_frame.h.
void ndt_feature_reg::PoseEstimator::matchFrames | ( | const NDTFrame & | f0, |
const NDTFrame & | f2, | ||
std::vector< cv::DMatch > & | fwd_matches | ||
) |
Definition at line 36 of file ndt_frame.hpp.
std::vector<cv::DMatch> ndt_feature_reg::PoseEstimator::inliers |
RANSAC inliers of matches.
Definition at line 369 of file ndt_frame.h.
cv::Ptr<cv::DescriptorMatcher> ndt_feature_reg::PoseEstimator::matcher |
Descriptor matcher to use (features_2d::BruteForceMatcher by default).
Definition at line 383 of file ndt_frame.h.
std::vector<cv::DMatch> ndt_feature_reg::PoseEstimator::matches |
Matches between features in frames.
Definition at line 368 of file ndt_frame.h.
Definition at line 379 of file ndt_frame.h.
Definition at line 377 of file ndt_frame.h.
Maximum dist^2 for inliers in pixels.
Definition at line 377 of file ndt_frame.h.
Definition at line 380 of file ndt_frame.h.
number of RANSAC iterations
Definition at line 371 of file ndt_frame.h.
Definition at line 391 of file ndt_frame.h.
Eigen::Quaterniond ndt_feature_reg::PoseEstimator::quat |
Definition at line 388 of file ndt_frame.h.
Eigen::Matrix3d ndt_feature_reg::PoseEstimator::rot |
Rotation matrix of camera between the frames.
Definition at line 387 of file ndt_frame.h.
Eigen::Vector3d ndt_feature_reg::PoseEstimator::trans |
Translation of the camera between the frames.
Definition at line 389 of file ndt_frame.h.
Whether to do windowed or whole-image matching.
Definition at line 374 of file ndt_frame.h.
Definition at line 384 of file ndt_frame.h.
Definition at line 384 of file ndt_frame.h.