pointcloud_normal.h
Go to the documentation of this file.
00001 #ifndef NORMAL_EXTRAPOLATION_H
00002 #define NORMAL_EXTRAPOLATION_H
00003 
00004 #include <vcg/space/index/kdtree/kdtree.h>
00005 #include <vcg/space/fitting3.h>
00006 #include <vcg/complex/algorithms/smooth.h>
00007 
00008 namespace vcg {
00009 namespace tri {
00011 
00013 
00014 
00015 
00016 
00017 template <typename MeshType>
00018 class PointCloudNormal {
00019 public:
00020 
00021   typedef typename MeshType::VertexType     VertexType;
00022   typedef typename MeshType::VertexType::CoordType     CoordType;
00023   typedef typename MeshType::VertexPointer  VertexPointer;
00024   typedef typename MeshType::VertexIterator VertexIterator;
00025   typedef typename MeshType::ScalarType                 ScalarType;
00026 
00027   class WArc
00028   {
00029   public:
00030     WArc(VertexPointer _s,VertexPointer _t):src(_s),trg(_t),w(fabs(_s->cN()*_t->cN())){}
00031 
00032     VertexPointer src;
00033     VertexPointer trg;
00034     float w;
00035     bool operator< (const WArc &a) const {return w<a.w;}
00036   };
00037 
00038   static void ComputeUndirectedNormal(MeshType &m, int nn, ScalarType maxDist, KdTree<ScalarType> &tree,vcg::CallBackPos * cb=0)
00039   {
00040 //    tree.setMaxNofNeighbors(nn);
00041     const ScalarType maxDistSquared = maxDist*maxDist;
00042     int cnt=0;
00043     int step=m.vn/100;
00044     typename KdTree<ScalarType>::PriorityQueue nq;
00045     for (VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00046     {
00047         tree.doQueryK(vi->cP(),nn,nq);
00048         if(cb && (++cnt%step)==0) cb(cnt/step,"Fitting planes");
00049 
00050 //        int neighbours = tree.getNofFoundNeighbors();
00051         int neighbours = nq.getNofElements();
00052         std::vector<CoordType> ptVec;
00053         for (int i = 0; i < neighbours; i++)
00054         {
00055 //            int neightId = tree.getNeighborId(i);
00056             int neightId = nq.getIndex(i);
00057             if(nq.getWeight(i) <maxDistSquared)
00058               ptVec.push_back(m.vert[neightId].cP());
00059         }
00060         Plane3<ScalarType> plane;
00061         FitPlaneToPointSet(ptVec,plane);
00062         vi->N()=plane.Direction();
00063     }
00064   }
00065 
00066   static void AddNeighboursToHeap( MeshType &m, VertexPointer vp, int nn, KdTree<ScalarType> &tree, std::vector<WArc> &heap)
00067   {
00068     typename KdTree<ScalarType>::PriorityQueue nq;
00069     tree.doQueryK(vp->cP(),nn,nq);
00070 
00071     int neighbours =  nq.getNofElements();
00072     for (int i = 0; i < neighbours; i++)
00073     {
00074 //        int neightId = tree.getNeighborId(i);
00075         int neightId = nq.getIndex(i);
00076         if (neightId < m.vn && (&m.vert[neightId] != vp))
00077         {
00078           if(!m.vert[neightId].IsV())
00079           {
00080             heap.push_back(WArc(vp,&(m.vert[neightId])));
00081             //std::push_heap(heap.begin(),heap.end());
00082             if(heap.back().w < 0.3f)
00083                 heap.pop_back();
00084             else
00085                 std::push_heap(heap.begin(),heap.end());
00086           }
00087         }
00088     }
00089     //std::push_heap(heap.begin(),heap.end());
00090   }
00093   struct Param
00094   {
00095     Param():
00096       fittingAdjNum(10),
00097       smoothingIterNum(0),
00098       coherentAdjNum(8),
00099       viewPoint(0,0,0),
00100       useViewPoint(false)
00101     {}
00102 
00103     int fittingAdjNum; 
00104     int smoothingIterNum; 
00105     int coherentAdjNum; 
00106     CoordType viewPoint;  
00107     bool useViewPoint;  
00108   };
00109 
00110   static void Compute(MeshType &m, Param p, vcg::CallBackPos * cb=0)
00111   {
00112     tri::Allocator<MeshType>::CompactVertexVector(m);
00113     if(cb) cb(1,"Building KdTree...");
00114     VertexConstDataWrapper<MeshType> DW(m);
00115     KdTree<ScalarType> tree(DW);
00116 
00117     ComputeUndirectedNormal(m, p.fittingAdjNum, std::numeric_limits<ScalarType>::max(), tree,cb);
00118 
00119     tri::Smooth<MeshType>::VertexNormalPointCloud(m,p.fittingAdjNum,p.smoothingIterNum,&tree);
00120 
00121     if(p.coherentAdjNum==0) return;
00122 //    tree.setMaxNofNeighbors(p.coherentAdjNum+1);
00123 
00124     tri::UpdateFlags<MeshType>::VertexClearV(m);
00125     std::vector<WArc> heap;
00126     VertexIterator vi=m.vert.begin();
00127 
00128     while(true)
00129     {
00130       // search an unvisited vertex
00131       while(vi!=m.vert.end() && vi->IsV())
00132         ++vi;
00133 
00134       if(vi==m.vert.end()) return;
00135 
00136       if ( p.useViewPoint &&
00137           ( vi->N().dot(p.viewPoint- vi->P())<0.0f) )
00138           vi->N()=-(*vi).N();
00139 
00140       vi->SetV();
00141       AddNeighboursToHeap(m,&*vi,p.coherentAdjNum,tree,heap);
00142 
00143       while(!heap.empty())
00144       {
00145         std::pop_heap(heap.begin(),heap.end());
00146         WArc a = heap.back();
00147         heap.pop_back();
00148         if(!a.trg->IsV())
00149         {
00150           a.trg->SetV();
00151           if(a.src->cN()*a.trg->cN()<0.0f)
00152             if(!p.useViewPoint || ( a.trg->N().dot(p.viewPoint- a.trg->P())<0.0f)) // test to prevent flipping according to viewpos
00153               a.trg->N()=-a.trg->N();
00154           AddNeighboursToHeap(m,a.trg,p.coherentAdjNum,tree,heap);
00155         }
00156       }
00157     }
00158 
00159     return;
00160   }
00161 
00162 };
00163 }//end namespace vcg
00164 }//end namespace vcg
00165 #endif // NORMAL_EXTRAPOLATION_H


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:34:25