#include <ndt_frame_proc.h>
Public Types | |
typedef Eigen::Transform < double, 3, Eigen::Affine, Eigen::ColMajor > | EigenTransform |
Public Member Functions | |
void | addFrame (NDTFrame *f) |
void | addFrameIncremental (NDTFrame *f, bool skipMatching, bool ndtEstimateDI=false, bool match_full=false, bool match_no_association=false) |
void | convertMatches (const std::vector< cv::DMatch > &in, std::vector< std::pair< int, int > > &out) |
std::vector< std::pair< int, int > > | convertMatches (const std::vector< cv::DMatch > &in) |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | createColoredFeaturePC (NDTFrame &f, pcl::PointXYZRGB color) |
NDTFrameProc (int nb_ransac, double max_inldist_xy, double max_inldist_z) | |
void | processFrames (bool skipMatching, bool ndtEstimateDI=false, bool match_full=false, bool match_no_association=false) |
void | trimNbFrames (size_t maxNbFrames) |
virtual | ~NDTFrameProc () |
Public Attributes | |
cv::Ptr< cv::FeatureDetector > | detector |
cv::Ptr< cv::DescriptorExtractor > | extractor |
std::vector< NDTFrame *, Eigen::aligned_allocator < NDTFrame > > | frames |
double | img_scale |
bool | non_mean |
PoseEstimator | pe |
std::vector< EigenTransform, Eigen::aligned_allocator < EigenTransform > > | transformVector |
double | trim_factor |
Private Member Functions | |
void | calcDescriptors (NDTFrame *f) const |
void | detectKeypoints (NDTFrame *f) const |
Definition at line 45 of file ndt_frame_proc.h.
typedef Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> ndt_feature_reg::NDTFrameProc::EigenTransform |
Reimplemented in ndt_feature_reg::ExpNDTFrameProc.
Definition at line 85 of file ndt_frame_proc.h.
ndt_feature_reg::NDTFrameProc::NDTFrameProc | ( | int | nb_ransac, |
double | max_inldist_xy, | ||
double | max_inldist_z | ||
) | [inline] |
Definition at line 72 of file ndt_frame_proc.h.
virtual ndt_feature_reg::NDTFrameProc::~NDTFrameProc | ( | ) | [inline, virtual] |
Definition at line 111 of file ndt_frame_proc.h.
void ndt_feature_reg::NDTFrameProc::addFrame | ( | NDTFrame * | f | ) | [inline] |
Definition at line 58 of file ndt_frame_proc.h.
void ndt_feature_reg::NDTFrameProc::addFrameIncremental | ( | NDTFrame * | f, |
bool | skipMatching, | ||
bool | ndtEstimateDI = false , |
||
bool | match_full = false , |
||
bool | match_no_association = false |
||
) |
Reimplemented in ndt_feature_reg::ExpNDTFrameProc.
Definition at line 8 of file ndt_frame_proc.hpp.
void ndt_feature_reg::NDTFrameProc::calcDescriptors | ( | NDTFrame * | f | ) | const [private] |
Reimplemented in ndt_feature_reg::ExpNDTFrameProc.
Definition at line 183 of file ndt_frame_proc.hpp.
void ndt_feature_reg::NDTFrameProc::convertMatches | ( | const std::vector< cv::DMatch > & | in, |
std::vector< std::pair< int, int > > & | out | ||
) | [inline] |
Definition at line 89 of file ndt_frame_proc.h.
std::vector<std::pair<int,int> > ndt_feature_reg::NDTFrameProc::convertMatches | ( | const std::vector< cv::DMatch > & | in | ) | [inline] |
Definition at line 99 of file ndt_frame_proc.h.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr ndt_feature_reg::NDTFrameProc::createColoredFeaturePC | ( | NDTFrame & | f, |
pcl::PointXYZRGB | color | ||
) |
Definition at line 203 of file ndt_frame_proc.hpp.
void ndt_feature_reg::NDTFrameProc::detectKeypoints | ( | NDTFrame * | f | ) | const [private] |
Reimplemented in ndt_feature_reg::ExpNDTFrameProc.
Definition at line 165 of file ndt_frame_proc.hpp.
void ndt_feature_reg::NDTFrameProc::processFrames | ( | bool | skipMatching, |
bool | ndtEstimateDI = false , |
||
bool | match_full = false , |
||
bool | match_no_association = false |
||
) |
Definition at line 88 of file ndt_frame_proc.hpp.
void ndt_feature_reg::NDTFrameProc::trimNbFrames | ( | size_t | maxNbFrames | ) |
Reimplemented in ndt_feature_reg::ExpNDTFrameProc.
Definition at line 72 of file ndt_frame_proc.hpp.
cv::Ptr<cv::FeatureDetector> ndt_feature_reg::NDTFrameProc::detector |
Definition at line 106 of file ndt_frame_proc.h.
cv::Ptr<cv::DescriptorExtractor> ndt_feature_reg::NDTFrameProc::extractor |
Definition at line 107 of file ndt_frame_proc.h.
std::vector< NDTFrame*,Eigen::aligned_allocator<NDTFrame > > ndt_feature_reg::NDTFrameProc::frames |
Definition at line 86 of file ndt_frame_proc.h.
Definition at line 108 of file ndt_frame_proc.h.
Definition at line 110 of file ndt_frame_proc.h.
Definition at line 84 of file ndt_frame_proc.h.
std::vector<EigenTransform, Eigen::aligned_allocator<EigenTransform> > ndt_feature_reg::NDTFrameProc::transformVector |
Definition at line 87 of file ndt_frame_proc.h.
Definition at line 109 of file ndt_frame_proc.h.