00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef __VCGLIB_CLUSTERING
00025 #define __VCGLIB_CLUSTERING
00026
00027 #include<vcg/complex/complex.h>
00028 #include <vcg/complex/algorithms/clean.h>
00029 #include<vcg/space/triangle3.h>
00030 #include<vcg/complex/algorithms/update/topology.h>
00031 #include<vcg/space/index/grid_util.h>
00032
00033 #include <iostream>
00034 #include <math.h>
00035 #include <limits>
00036 #include <unordered_set>
00037 #include <unordered_map>
00038
00039 namespace std
00040 {
00041 template<>
00042 struct hash<vcg::Point3i>
00043 {
00044 typedef vcg::Point3i argument_type;
00045
00046 std::size_t operator()(const vcg::Point3i & s) const
00047 {
00048 return std::hash<int>()(s[0]) ^ std::hash<int>()(s[1]) ^ std::hash<int>()(s[2]);
00049 }
00050 };
00051 }
00052
00053 namespace vcg{
00054 namespace tri{
00055
00056 template<class MeshType >
00057 class NearestToCenter
00058 {
00059 typedef typename MeshType::ScalarType ScalarType;
00060 typedef typename MeshType::CoordType CoordType;
00061 typedef typename MeshType::VertexType VertexType;
00062 typedef typename MeshType::FaceType FaceType;
00063 typedef BasicGrid<typename MeshType::ScalarType> GridType;
00064
00065 public:
00066 inline void AddVertex(MeshType &, GridType &g, Point3i &pi, VertexType &v)
00067 {
00068 CoordType c;
00069 g.IPiToBoxCenter(pi,c);
00070 ScalarType newDist = Distance(c,v.cP());
00071 if(!valid || newDist < bestDist)
00072 {
00073 valid=true;
00074 bestDist=newDist;
00075 bestPos=v.cP();
00076 bestN=v.cN();
00077 orig=&v;
00078 }
00079 }
00080 inline void AddFaceVertex(MeshType &, FaceType &, int ) { assert(0);}
00081 NearestToCenter(): valid(false){}
00082
00083 CoordType bestPos;
00084 CoordType bestN;
00085 ScalarType bestDist;
00086 bool valid;
00087 int id;
00088 VertexType *orig;
00089 CoordType Pos() const
00090 {
00091 assert(valid);
00092 return bestPos;
00093 }
00094 Color4b Col() const {return Color4b::White;}
00095 CoordType N() const {return bestN;}
00096 VertexType * Ptr() const {return orig;}
00097
00098 };
00099
00100 template<class MeshType>
00101 class AverageColorCell
00102 {
00103 typedef typename MeshType::CoordType CoordType;
00104 typedef typename MeshType::FaceType FaceType;
00105 typedef typename MeshType::VertexType VertexType;
00106
00107 typedef BasicGrid<typename MeshType::ScalarType> GridType;
00108
00109 public:
00110 inline void AddFaceVertex(MeshType &, FaceType &f, int i)
00111 {
00112 p+=f.cV(i)->cP();
00113 c+=CoordType(f.cV(i)->C()[0],f.cV(i)->C()[1],f.cV(i)->C()[2]);
00114
00115
00116
00117 n+=f.cN();
00118 cnt++;
00119 }
00120 inline void AddVertex(MeshType &m, GridType &, Point3i &, VertexType &v)
00121 {
00122 p+=v.cP();
00123 n+=v.cN();
00124 if(tri::HasPerVertexColor(m))
00125 c+=CoordType(v.C()[0],v.C()[1],v.C()[2]);
00126 cnt++;
00127 }
00128
00129 AverageColorCell(): p(0,0,0), n(0,0,0), c(0,0,0),cnt(0){}
00130 CoordType p;
00131 CoordType n;
00132 CoordType c;
00133 int cnt;
00134 int id;
00135 Color4b Col() const
00136 {
00137 return Color4b(c[0]/cnt,c[1]/cnt,c[2]/cnt,255);
00138 }
00139
00140 CoordType N() const {return n;}
00141 VertexType * Ptr() const {return 0;}
00142 CoordType Pos() const { return p/cnt; }
00143 };
00144
00145
00146
00147
00148
00149 template<class MeshType, class CellType>
00150 class Clustering
00151 {
00152 public:
00153 typedef typename MeshType::ScalarType ScalarType;
00154 typedef typename MeshType::CoordType CoordType;
00155 typedef typename MeshType::VertexType VertexType;
00156 typedef typename MeshType::FaceType FaceType;
00157 typedef typename MeshType::VertexPointer VertexPointer;
00158 typedef typename MeshType::VertexIterator VertexIterator;
00159 typedef typename MeshType::FaceIterator FaceIterator;
00160
00161
00162
00163
00164
00165
00166
00167 bool DuplicateFaceParam;
00168
00169
00170 class SimpleTri
00171 {
00172 public:
00173 CellType *v[3];
00174 int ii(int i) const {return *((int *)(&(v[i])));}
00175 bool operator < ( const SimpleTri &p) const {
00176 return (v[2]!=p.v[2])?(v[2]<p.v[2]):
00177 (v[1]!=p.v[1])?(v[1]<p.v[1]):
00178 (v[0]<p.v[0]);
00179 }
00180
00181
00182 void sortOrient()
00183 {
00184 if(v[1] < v[0] && v[1] < v[2] ) { std::swap(v[0],v[1]); std::swap(v[1],v[2]); return; }
00185 if(v[2] < v[0] && v[2] < v[1] ) { std::swap(v[0],v[2]); std::swap(v[1],v[2]); return; }
00186 return;
00187 }
00188 void sort()
00189 {
00190 if(v[0] > v[1] ) std::swap(v[0],v[1]);
00191 if(v[0] > v[2] ) std::swap(v[0],v[2]);
00192 if(v[1] > v[2] ) std::swap(v[1],v[2]);
00193 }
00194 bool operator ==(const SimpleTri &pt) const
00195 {
00196 return (pt.v[0] == v[0])
00197 && (pt.v[1] == v[1])
00198 && (pt.v[2] == v[2]);
00199 }
00200
00201 size_t operator () (const SimpleTri &pt) const
00202 {
00203
00204 return std::hash<CellType*>()(pt.v[0]) ^ std::hash<CellType*>()(pt.v[1]) ^ std::hash<CellType*>()(pt.v[2]);
00205 }
00206 };
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220 void Init(Box3<ScalarType> _mbb, int _size, ScalarType _cellsize=0)
00221 {
00222 GridCell.clear();
00223 TriSet.clear();
00224 Grid.bbox=_mbb;
00226 ScalarType infl = (_cellsize == (ScalarType)0) ? (Grid.bbox.Diag() / _size) : (_cellsize);
00227 Grid.bbox.min-=CoordType(infl,infl,infl);
00228 Grid.bbox.max+=CoordType(infl,infl,infl);
00229 Grid.dim = Grid.bbox.max - Grid.bbox.min;
00230 if( _cellsize==0)
00231 BestDim( _size, Grid.dim, Grid.siz );
00232 else
00233 Grid.siz = Point3i::Construct(Grid.dim / _cellsize);
00234
00235
00236 Grid.voxel[0] = Grid.dim[0]/Grid.siz[0];
00237 Grid.voxel[1] = Grid.dim[1]/Grid.siz[1];
00238 Grid.voxel[2] = Grid.dim[2]/Grid.siz[2];
00239 }
00240
00241 BasicGrid<ScalarType> Grid;
00242
00243 std::unordered_set<SimpleTri,SimpleTri> TriSet;
00244 typedef typename std::unordered_set<SimpleTri,SimpleTri>::iterator TriHashSetIterator;
00245 std::unordered_map<Point3i,CellType> GridCell;
00246
00247
00248 void AddPointSet(MeshType &m, bool UseOnlySelected=false)
00249 {
00250 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00251 if(!(*vi).IsD())
00252 if(!UseOnlySelected || (*vi).IsS())
00253 {
00254 Point3i pi;
00255 Grid.PToIP((*vi).cP(), pi );
00256 GridCell[pi].AddVertex(m,Grid,pi,*(vi));
00257 }
00258 }
00259
00260 void AddMesh(MeshType &m)
00261 {
00262 FaceIterator fi;
00263 for(fi=m.face.begin();fi!=m.face.end();++fi) if(!(*fi).IsD())
00264 {
00265 Point3i pi;
00266 SimpleTri st;
00267 for(int i=0;i<3;++i)
00268 {
00269 Grid.PToIP((*fi).cV(i)->cP(), pi );
00270 st.v[i]=&(GridCell[pi]);
00271 st.v[i]->AddFaceVertex(m,*(fi),i);
00272 }
00273 if( (st.v[0]!=st.v[1]) && (st.v[0]!=st.v[2]) && (st.v[1]!=st.v[2]) )
00274 {
00275 if(DuplicateFaceParam) st.sortOrient();
00276 else st.sort();
00277 TriSet.insert(st);
00278 }
00279
00280 }
00281 }
00282
00283 int CountPointSet() {return GridCell.size(); }
00284
00285 void SelectPointSet(MeshType &m)
00286 {
00287 typename std::unordered_map<Point3i,CellType>::iterator gi;
00288 UpdateSelection<MeshType>::VertexClear(m);
00289 for(gi=GridCell.begin();gi!=GridCell.end();++gi)
00290 {
00291 VertexType *ptr=(*gi).second.Ptr();
00292 if(ptr && ( ptr >= &*m.vert.begin() ) && ( ptr <= &*(m.vert.end() - 1) ) )
00293 ptr->SetS();
00294 }
00295 }
00296 void ExtractPointSet(MeshType &m)
00297 {
00298 m.Clear();
00299
00300 if (GridCell.empty()) return;
00301
00302 Allocator<MeshType>::AddVertices(m,GridCell.size());
00303 typename std::unordered_map<Point3i,CellType>::iterator gi;
00304 int i=0;
00305 for(gi=GridCell.begin();gi!=GridCell.end();++gi)
00306 {
00307 m.vert[i].P()=(*gi).second.Pos();
00308 m.vert[i].N()=(*gi).second.N();
00309 if(HasPerVertexColor(m))
00310 m.vert[i].C()=(*gi).second.Col();
00311 ++i;
00312 }
00313
00314 }
00315
00316 void ExtractMesh(MeshType &m)
00317 {
00318 m.Clear();
00319
00320 if (GridCell.empty()) return;
00321
00322 Allocator<MeshType>::AddVertices(m,GridCell.size());
00323 typename std::unordered_map<Point3i,CellType>::iterator gi;
00324 int i=0;
00325 for(gi=GridCell.begin();gi!=GridCell.end();++gi)
00326 {
00327 m.vert[i].P()=(*gi).second.Pos();
00328 m.vert[i].N()=(*gi).second.N();
00329 if(HasPerVertexColor(m))
00330 m.vert[i].C()=(*gi).second.Col();
00331 (*gi).second.id=i;
00332 ++i;
00333 }
00334
00335 Allocator<MeshType>::AddFaces(m,TriSet.size());
00336 TriHashSetIterator ti;
00337 i=0;
00338 for(ti=TriSet.begin();ti!=TriSet.end();++ti)
00339 {
00340 m.face[i].V(0)=&(m.vert[(*ti).v[0]->id]);
00341 m.face[i].V(1)=&(m.vert[(*ti).v[1]->id]);
00342 m.face[i].V(2)=&(m.vert[(*ti).v[2]->id]);
00343
00344
00345 if(!DuplicateFaceParam)
00346 {
00347 CoordType N=TriangleNormal(m.face[i]);
00348 int badOrient=0;
00349 if( N.dot((*ti).v[0]->N()) <0) ++badOrient;
00350 if( N.dot((*ti).v[1]->N()) <0) ++badOrient;
00351 if( N.dot((*ti).v[2]->N()) <0) ++badOrient;
00352 if(badOrient>2)
00353 std::swap(m.face[i].V(0),m.face[i].V(1));
00354 }
00355 i++;
00356 }
00357
00358 }
00359 };
00360 }
00361 }
00362
00363 #endif