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