ndt_frame_proc.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, AASS Research Center, Orebro University.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of AASS Research Center nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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 //        bool loadImg(NDTFrame<PointT> &f, const std::string &fileName) const;
00049 //        void loadPC(NDTFrame<PointT> &f, const std::string &fileName) const;
00050 
00051 //        bool loadPCfromDepth(NDTFrame<PointT> &f, const std::string &fileName) const;
00052 
00053 //        bool setupDepthToPC(const std::string &fileName, double fx, double fy, double cx, double cy, const std::vector<double> &dist, double ds);
00054 //        void setupDepthToPC(const cv::Mat &depthImg, double fx, double fy, double cx, double cy, const std::vector<double> &dist, double ds);
00055 
00056 //        void convertDepthToPC(const cv::Mat &depthImg, pcl::PointCloud<PointT> &pc) const;
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 //        lslgeneric::NDTMatcherFeatureD2D<PointT,PointT> *matcher_feat; //(corr);
00127 
00128 
00129 };
00130 
00131 
00132 
00133 } // namespace
00134 
00135 //#include <ndt_feature_reg/impl/ndt_frame_proc.hpp>
00136 #endif


ndt_feature_reg
Author(s): Henrik Andreasson, Todor Stoyanov, Jari Saarinen
autogenerated on Wed Aug 26 2015 15:25:07