Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
normals_estimator.hpp
00001 /* $ Id: $*/
00002 
00003 #ifndef NORMALS_ESTIMATOR_HPP
00004 #define NORMALS_ESTIMATOR_HPP
00005 #include "kernel/csvFile.hpp"
00006 #include "jmath/jblas.hpp"
00007 #include "jmath/pca.hpp"
00008 #include "jmath/jann.hpp"
00009 #include "kernel/jafarMacro.hpp"
00010 
00011 namespace jafar {
00012   namespace modeler {
00013 
00014     class normals_estimator {
00015     private:
00017       size_t m_knn;
00019     public:
00021       ublas::matrix<double> m_cloud;
00022     private:
00023       jann::KD_tree_index< flann::L2<double> > m_index;
00025       jmath::PCA pca;
00027       size_t K;
00029       jblas::vec compute_normal(const ublas::matrix<double>& Q);
00030 
00031     public:
00032       normals_estimator(size_t k=25) : m_knn(k) {};
00033 
00034       normals_estimator(const ublas::matrix<double>& set, size_t k=25) : 
00035         m_knn(k), m_cloud (set), m_index(m_cloud, 4) {
00036         JFR_ASSERT(m_cloud.size2() == 3, "for now can handle only 3 dimension");
00037         JFR_ASSERT(m_cloud.size1() > m_knn, "nbr of points must exceed nbr of neighbours");
00038       }
00039 
00040       normals_estimator(const std::map<size_t, jblas::vec3>& points, 
00041                         size_t k = 25) : 
00042         m_knn(k), m_cloud(points.size(), 3) {
00043         JFR_ASSERT(points.size() > m_knn, "points size must be at least "<<m_knn);
00044         size_t i = 0;
00045         for(std::map<size_t, jblas::vec3>::const_iterator iter = points.begin(); 
00046             iter != points.end();
00047             ++iter, ++i) {
00048           row(m_cloud, i) = iter->second;
00049         }
00050         m_index(m_cloud, 4); 
00051       }
00052 
00053       jblas::vec estimate(int index);
00054 
00055       ublas::matrix<double> batch_estimate();
00056     };
00057   }
00058 }
00059 
00060 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:25 for Jafar by doxygen 1.7.6.1
LAAS-CNRS