Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef NDTFRAMEPROC_HH
00036 #define NDTFRAMEPROC_HH
00037
00038 #include <ndt_feature_reg/ndt_frame.h>
00039 #include <ndt_registration/ndt_matcher_d2d_feature.h>
00040 #include <opencv2/nonfree/features2d.hpp>
00041 #include <opencv2/nonfree/nonfree.hpp>
00042
00043 namespace ndt_feature_reg
00044 {
00045 class NDTFrameProc
00046 {
00047 public:
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058 void addFrame (NDTFrame *f)
00059 {
00060 frames.push_back(f);
00061 }
00062
00063 void addFrameIncremental (NDTFrame *f, bool skipMatching, bool ndtEstimateDI = false,
00064 bool match_full = false, bool match_no_association = false);
00065 void trimNbFrames (size_t maxNbFrames);
00066
00067 void processFrames (bool skipMatching, bool ndtEstimateDI = false,
00068 bool match_full = false, bool match_no_association = false);
00069
00070 pcl::PointCloud<pcl::PointXYZRGB>::Ptr createColoredFeaturePC(NDTFrame &f, pcl::PointXYZRGB color);
00071
00072 NDTFrameProc(int nb_ransac, double max_inldist_xy, double max_inldist_z): pe(nb_ransac, max_inldist_xy, max_inldist_z)
00073 {
00074 detector = cv::FeatureDetector::create("SURF");
00075 extractor = cv::DescriptorExtractor::create("SURF");
00076 img_scale = 1.;
00077 trim_factor = 1.;
00078 non_mean = false;
00079 cv::initModule_nonfree();
00080 cv::initModule_features2d();
00081
00082 }
00083
00084 PoseEstimator pe;
00085 typedef Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> EigenTransform;
00086 typename std::vector< NDTFrame*,Eigen::aligned_allocator<NDTFrame > > frames;
00087 typename std::vector<EigenTransform, Eigen::aligned_allocator<EigenTransform> > transformVector;
00088
00089 inline void convertMatches(const std::vector<cv::DMatch> &in, std::vector<std::pair<int,int> > &out)
00090 {
00091 out.resize(in.size());
00092 for (size_t i = 0; i < in.size(); i++)
00093 {
00094 out[i].first = in[i].queryIdx;
00095 out[i].second = in[i].trainIdx;
00096 }
00097 }
00098
00099 inline std::vector<std::pair<int,int> > convertMatches(const std::vector<cv::DMatch> &in)
00100 {
00101 std::vector<std::pair<int,int> > out;
00102 convertMatches(in,out);
00103 return out;
00104 }
00105
00106 cv::Ptr<cv::FeatureDetector> detector;
00107 cv::Ptr<cv::DescriptorExtractor> extractor;
00108 double img_scale;
00109 double trim_factor;
00110 bool non_mean;
00111 virtual ~NDTFrameProc()
00112 {
00113 for(size_t i =0; i<frames.size(); i++)
00114 {
00115 delete frames[i];
00116 }
00117 frames.clear();
00118 }
00119 private:
00120
00121 void detectKeypoints(NDTFrame *f) const;
00122 void calcDescriptors(NDTFrame *f) const;
00123 public:
00124 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00125
00126
00127
00128
00129 };
00130
00131
00132
00133 }
00134
00135
00136 #endif