00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #ifndef __VCG_MESH_RESAMPLER
00024 #define __VCG_MESH_RESAMPLER
00025
00026 #include <vcg/complex/algorithms/update/normal.h>
00027 #include <vcg/complex/algorithms/update/flag.h>
00028 #include <vcg/complex/algorithms/update/bounding.h>
00029 #include <vcg/complex/algorithms/update/component_ep.h>
00030 #include <vcg/complex/algorithms/create/marching_cubes.h>
00031 #include <vcg/space/index/grid_static_ptr.h>
00032 #include <vcg/complex/algorithms/closest.h>
00033 #include <vcg/space/box3.h>
00034
00035 namespace vcg {
00036 namespace tri {
00037
00038
00041
00049 template <class OldMeshType,
00050 class NewMeshType,
00051 class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType > >
00052 class Resampler : public BasicGrid<typename NewMeshType::ScalarType>
00053 {
00054 typedef typename NewMeshType::ScalarType NewScalarType;
00055 typedef typename NewMeshType::BoxType NewBoxType;
00056 typedef typename NewMeshType::CoordType NewCoordType;
00057 typedef typename NewMeshType::VertexType* NewVertexPointer;
00058 typedef typename NewMeshType::VertexIterator NewVertexIterator;
00059 typedef typename OldMeshType::CoordType OldCoordType;
00060 typedef typename OldMeshType::FaceContainer OldFaceCont;
00061 typedef typename OldMeshType::FaceType OldFaceType;
00062 typedef typename OldMeshType::ScalarType OldScalarType;
00063
00064 class Walker : BasicGrid<typename NewMeshType::ScalarType>
00065 {
00066 private:
00067 typedef int VertexIndex;
00068 typedef typename vcg::GridStaticPtr<OldFaceType, OldScalarType> GridType;
00069
00070 protected:
00071
00072 int SliceSize;
00073 int CurrentSlice;
00074 typedef tri::FaceTmark<OldMeshType> MarkerFace;
00075 MarkerFace markerFunctor;
00076
00077 VertexIndex *_x_cs;
00078 VertexIndex *_y_cs;
00079 VertexIndex *_z_cs;
00080 VertexIndex *_x_ns;
00081 VertexIndex *_z_ns;
00082
00083
00084
00085
00086 typedef typename std::pair<bool,float> field_value;
00087 field_value* _v_cs;
00088 field_value* _v_ns;
00089
00090 NewMeshType *_newM;
00091 OldMeshType *_oldM;
00092 GridType _g;
00093
00094 public:
00095 NewScalarType max_dim;
00096 NewScalarType offset;
00097 bool DiscretizeFlag;
00098 bool MultiSampleFlag;
00099 bool AbsDistFlag;
00100 Walker(const Box3<NewScalarType> &_bbox, Point3i _siz )
00101 {
00102 this->bbox= _bbox;
00103 this->siz=_siz;
00104 this->ComputeDimAndVoxel();
00105
00106 SliceSize = (this->siz.X()+1)*(this->siz.Z()+1);
00107 CurrentSlice = 0;
00108 offset=0;
00109 DiscretizeFlag=false;
00110 MultiSampleFlag=false;
00111 AbsDistFlag=false;
00112
00113 _x_cs = new VertexIndex[ SliceSize ];
00114 _y_cs = new VertexIndex[ SliceSize ];
00115 _z_cs = new VertexIndex[ SliceSize ];
00116 _x_ns = new VertexIndex[ SliceSize ];
00117 _z_ns = new VertexIndex[ SliceSize ];
00118
00119 _v_cs= new field_value[(this->siz.X()+1)*(this->siz.Z()+1)];
00120 _v_ns= new field_value[(this->siz.X()+1)*(this->siz.Z()+1)];
00121
00122 };
00123
00124 ~Walker()
00125 {}
00126
00127
00128 NewScalarType V(const Point3i &p)
00129 {
00130 return V(p.V(0),p.V(1),p.V(2));
00131 }
00132
00133
00134 std::pair<bool,NewScalarType> VV(int x,int y,int z)
00135 {
00136 assert ((y==CurrentSlice)||(y==(CurrentSlice+1)));
00137
00138
00139
00140
00141
00142 int index=GetSliceIndex(x,z);
00143
00144 if (y==CurrentSlice) return _v_cs[index];
00145 else return _v_ns[index];
00146 }
00147
00148 NewScalarType V(int x,int y,int z)
00149 {
00150 if(DiscretizeFlag) return VV(x,y,z).second+offset<0?-1:1;
00151 return VV(x,y,z).second+offset;
00152 }
00154 field_value DistanceFromMesh(OldCoordType &pp)
00155 {
00156 OldScalarType dist;
00157 const NewScalarType max_dist = max_dim;
00158 OldCoordType testPt;
00159 this->IPfToPf(pp,testPt);
00160
00161 OldCoordType closestPt;
00162 DISTFUNCTOR PDistFunct;
00163 OldFaceType *f = _g.GetClosest(PDistFunct,markerFunctor,testPt,max_dist,dist,closestPt);
00164 if (f==NULL) return field_value(false,0);
00165 if(AbsDistFlag) return field_value(true,dist);
00166 assert(!f->IsD());
00167 bool retIP;
00168
00169
00170 OldCoordType pip(-1,-1,-1);
00171 retIP=InterpolationParameters(*f,(*f).cN(),closestPt, pip);
00172 assert(retIP);
00173
00174 const NewScalarType InterpolationEpsilon = 0.00001f;
00175 int zeroCnt=0;
00176 if(pip[0]<InterpolationEpsilon) ++zeroCnt;
00177 if(pip[1]<InterpolationEpsilon) ++zeroCnt;
00178 if(pip[2]<InterpolationEpsilon) ++zeroCnt;
00179 assert(zeroCnt<3);
00180
00181 OldCoordType dir=(testPt-closestPt).Normalize();
00182
00183
00184
00185 NewScalarType signBest;
00186
00187
00188
00189 OldCoordType closestNormV, closestNormF;
00190 if(zeroCnt>0)
00191 {
00192 closestNormV = (f->V(0)->cN())*pip[0] + (f->V(1)->cN())*pip[1] + (f->V(2)->cN())*pip[2] ;
00193 signBest = dir.dot(closestNormV) ;
00194 }
00195 else
00196 {
00197 closestNormF = f->cN() ;
00198 signBest = dir.dot(closestNormF) ;
00199 }
00200
00201 if(signBest<0) dist=-dist;
00202
00203 return field_value(true,dist);
00204 }
00205
00206 field_value MultiDistanceFromMesh(OldCoordType &pp)
00207 {
00208 float distSum=0;
00209 int positiveCnt=0;
00210 const int MultiSample=7;
00211 const OldCoordType delta[7]={OldCoordType(0,0,0),
00212 OldCoordType( 0.2, -0.01, -0.02),
00213 OldCoordType(-0.2, 0.01, 0.02),
00214 OldCoordType( 0.01, 0.2, 0.01),
00215 OldCoordType( 0.03, -0.2, -0.03),
00216 OldCoordType(-0.02, -0.03, 0.2 ),
00217 OldCoordType(-0.01, 0.01, -0.2 )};
00218
00219 for(int qq=0;qq<MultiSample;++qq)
00220 {
00221 OldCoordType pp2=pp+delta[qq];
00222 field_value ff= DistanceFromMesh(pp2);
00223 if(ff.first==false) return field_value(false,0);
00224 distSum += fabs(ff.second);
00225 if(ff.second>0) positiveCnt ++;
00226 }
00227 if(positiveCnt<=MultiSample/2) distSum = -distSum;
00228 return field_value(true, distSum/MultiSample);
00229 }
00230
00233 void ComputeSliceValues(int slice,field_value *slice_values)
00234 {
00235 for (int i=0; i<=this->siz.X(); i++)
00236 {
00237 for (int k=0; k<=this->siz.Z(); k++)
00238 {
00239 int index=GetSliceIndex(i,k);
00240 OldCoordType pp(i,slice,k);
00241 if(this->MultiSampleFlag) slice_values[index] = MultiDistanceFromMesh(pp);
00242 else slice_values[index] = DistanceFromMesh(pp);
00243 }
00244 }
00245
00246 }
00247
00248
00249
00250
00251
00252 void ComputeConsensus(int , field_value *slice_values)
00253 {
00254 float max_dist = min(min(this->voxel[0],this->voxel[1]),this->voxel[2]);
00255 int flippedCnt=0;
00256 int flippedTot=0;
00257 int flippedTimes=0;
00258 do
00259 {
00260 flippedCnt=0;
00261 for (int i=0; i<=this->siz.X(); i++)
00262 {
00263 for (int k=0; k<=this->siz.Z(); k++)
00264 {
00265 int goodCnt=0;
00266 int badCnt=0;
00267 int index=GetSliceIndex(i,k);
00268 int index_l,index_r,index_u,index_d;
00269 if(slice_values[index].first)
00270 {
00271 float curVal= slice_values[index].second;
00272 if(i > 0 ) index_l=GetSliceIndex(i-1,k); else index_l = index;
00273 if(i < this->siz.X() ) index_r=GetSliceIndex(i+1,k); else index_r = index;
00274 if(k > 0 ) index_d=GetSliceIndex(i,k-1); else index_d = index;
00275 if(k < this->siz.Z() ) index_u=GetSliceIndex(i,k+1); else index_u = index;
00276
00277 if(slice_values[index_l].first) { goodCnt++; if(fabs(slice_values[index_l].second - curVal) > max_dist) badCnt++; }
00278 if(slice_values[index_r].first) { goodCnt++; if(fabs(slice_values[index_r].second - curVal) > max_dist) badCnt++; }
00279 if(slice_values[index_u].first) { goodCnt++; if(fabs(slice_values[index_u].second - curVal) > max_dist) badCnt++; }
00280 if(slice_values[index_d].first) { goodCnt++; if(fabs(slice_values[index_d].second - curVal) > max_dist) badCnt++; }
00281
00282 if(badCnt >= goodCnt) {
00283 slice_values[index].second *=-1.0f;
00284
00285 flippedCnt++;
00286 }
00287 }
00288 }
00289 }
00290 flippedTot+=flippedCnt;
00291 flippedTimes++;
00292 } while(flippedCnt>0);
00293
00294
00295 #ifdef QT_VERSION
00296 if(flippedTot>0)
00297 qDebug("Flipped %i values in %i times",flippedTot,flippedTimes);
00298 #endif
00299 }
00300 template<class EXTRACTOR_TYPE>
00301 void ProcessSlice(EXTRACTOR_TYPE &extractor)
00302 {
00303 for (int i=0; i<this->siz.X(); i++)
00304 {
00305 for (int k=0; k<this->siz.Z(); k++)
00306 {
00307 bool goodCell=true;
00308 Point3i p1(i,CurrentSlice,k);
00309 Point3i p2=p1+Point3i(1,1,1);
00310 for(int ii=0;ii<2;++ii)
00311 for(int jj=0;jj<2;++jj)
00312 for(int kk=0;kk<2;++kk)
00313 goodCell &= VV(p1[0]+ii,p1[1]+jj,p1[2]+kk).first;
00314
00315 if(goodCell) extractor.ProcessCell(p1, p2);
00316 }
00317 }
00318 }
00319
00320
00321 template<class EXTRACTOR_TYPE>
00322 void BuildMesh(OldMeshType &old_mesh,NewMeshType &new_mesh,EXTRACTOR_TYPE &extractor,vcg::CallBackPos *cb)
00323 {
00324 _newM=&new_mesh;
00325 _oldM=&old_mesh;
00326
00327
00328 tri::UpdateNormal<OldMeshType>::PerFaceNormalized(old_mesh);
00329 tri::UpdateNormal<OldMeshType>::PerVertexAngleWeighted(old_mesh);
00330 int _size=(int)old_mesh.fn*100;
00331
00332 _g.Set(_oldM->face.begin(),_oldM->face.end(),_size);
00333 markerFunctor.SetMesh(&old_mesh);
00334
00335 _newM->Clear();
00336
00337 Begin();
00338 extractor.Initialize();
00339 for (int j=0; j<=this->siz.Y(); j++)
00340 {
00341 if (cb) cb((100*j)/this->siz.Y(),"Marching ");
00342 ProcessSlice<EXTRACTOR_TYPE>(extractor);
00343 NextSlice();
00344 }
00345 extractor.Finalize();
00346 for(NewVertexIterator vi=new_mesh.vert.begin();vi!=new_mesh.vert.end();++vi)
00347 if(!(*vi).IsD())
00348 {
00349 this->IPfToPf((*vi).cP(),(*vi).P());
00350 }
00351 }
00352
00353
00354 int GetSliceIndex(int x,int z)
00355 {
00356 VertexIndex index = x+z*(this->siz.X()+1);
00357 return (index);
00358 }
00359
00360
00361 void NextSlice()
00362 {
00363
00364 memset(_x_cs, -1, SliceSize*sizeof(VertexIndex));
00365 memset(_y_cs, -1, SliceSize*sizeof(VertexIndex));
00366 memset(_z_cs, -1, SliceSize*sizeof(VertexIndex));
00367
00368
00369 std::swap(_x_cs, _x_ns);
00370 std::swap(_z_cs, _z_ns);
00371
00372 std::swap(_v_cs, _v_ns);
00373
00374 CurrentSlice ++;
00375
00376 ComputeSliceValues(CurrentSlice + 1,_v_ns);
00377 }
00378
00379
00380 void Begin()
00381 {
00382
00383 CurrentSlice = 0;
00384
00385 memset(_x_cs, -1, SliceSize*sizeof(VertexIndex));
00386 memset(_y_cs, -1, SliceSize*sizeof(VertexIndex));
00387 memset(_z_cs, -1, SliceSize*sizeof(VertexIndex));
00388 memset(_x_ns, -1, SliceSize*sizeof(VertexIndex));
00389 memset(_z_ns, -1, SliceSize*sizeof(VertexIndex));
00390
00391 ComputeSliceValues(CurrentSlice,_v_cs);
00392 ComputeSliceValues(CurrentSlice+1,_v_ns);
00393 }
00394
00395
00396
00397
00398 bool Exist(const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
00399 {
00400 int i = p1.X();
00401 int z = p1.Z();
00402 VertexIndex index = i+z*this->siz.X();
00403
00404
00405 int v_ind = 0;
00406 if (p1.X()!=p2.X())
00407 {
00408 if (p1.Y()==CurrentSlice)
00409 {
00410 if (_x_cs[index]!=-1)
00411 {
00412 v_ind = _x_cs[index];
00413 v = &_newM->vert[v_ind];
00414 assert(!v->IsD());
00415 return true;
00416 }
00417
00418 }
00419 else
00420 {
00421 if (_x_ns[index]!=-1)
00422 {
00423 v_ind = _x_ns[index];
00424 v = &_newM->vert[v_ind];
00425 assert(!v->IsD());
00426 return true;
00427 }
00428 }
00429 v = NULL;
00430 return false;
00431 }
00432 else if (p1.Y()!=p2.Y())
00433 {
00434 if (_y_cs[index]!=-1)
00435 {
00436 v_ind =_y_cs[index];
00437 v = &_newM->vert[v_ind];
00438 assert(!v->IsD());
00439 return true;
00440 }
00441 else
00442 {
00443 v = NULL;
00444 return false;
00445 }
00446
00447 }
00448 else if (p1.Z()!=p2.Z())
00449
00450 {
00451 if (p1.Y()==CurrentSlice)
00452 {
00453 if ( _z_cs[index]!=-1)
00454 {
00455 v_ind = _z_cs[index];
00456 v = &_newM->vert[v_ind];
00457 assert(!v->IsD());
00458 return true;
00459 }
00460
00461 }
00462 else
00463 {
00464 if (_z_ns[index]!=-1)
00465 {
00466 v_ind = _z_ns[index];
00467 v = &_newM->vert[v_ind];
00468 assert(!v->IsD());
00469 return true;
00470 }
00471 }
00472 v = NULL;
00473 return false;
00474 }
00475 assert (0);
00476 return false;
00477 }
00478
00480 NewCoordType Interpolate(const vcg::Point3i &p1, const vcg::Point3i &p2,int dir)
00481 {
00482 NewScalarType f1 = V(p1);
00483 NewScalarType f2 = V(p2);
00484 NewScalarType u = f1/(f1-f2);
00485 NewCoordType ret(p1.V(0),p1.V(1),p1.V(2));
00486 ret.V(dir) = p1.V(dir)*(1.f-u) + u*p2.V(dir);
00487 return (ret);
00488 }
00489
00491 void GetXIntercept(const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
00492 {
00493 assert(p1.X()+1 == p2.X());
00494 assert(p1.Y() == p2.Y());
00495 assert(p1.Z() == p2.Z());
00496
00497 int i = p1.X();
00498 int z = p1.Z();
00499 VertexIndex index = i+z*this->siz.X();
00500 VertexIndex pos=-1;
00501 if (p1.Y()==CurrentSlice)
00502 {
00503 if ((pos=_x_cs[index])==-1)
00504 {
00505 _x_cs[index] = (VertexIndex) _newM->vert.size();
00506 pos = _x_cs[index];
00507 Allocator<NewMeshType>::AddVertices( *_newM, 1 );
00508 v = &_newM->vert[pos];
00509 v->P()=Interpolate(p1,p2,0);
00510 return;
00511 }
00512 }
00513 if (p1.Y()==CurrentSlice+1)
00514 {
00515 if ((pos=_x_ns[index])==-1)
00516 {
00517 _x_ns[index] = (VertexIndex) _newM->vert.size();
00518 pos = _x_ns[index];
00519 Allocator<NewMeshType>::AddVertices( *_newM, 1 );
00520 v = &_newM->vert[pos];
00521 v->P()=Interpolate(p1,p2,0);
00522 return;
00523 }
00524 }
00525 assert(pos>=0);
00526 v = &_newM->vert[pos];
00527 }
00528
00530 void GetYIntercept(const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
00531 {
00532 assert(p1.X() == p2.X());
00533 assert(p1.Y()+1 == p2.Y());
00534 assert(p1.Z() == p2.Z());
00535
00536 int i = p1.X();
00537 int z = p1.Z();
00538 VertexIndex index = i+z*this->siz.X();
00539 VertexIndex pos=-1;
00540 if ((pos=_y_cs[index])==-1)
00541 {
00542 _y_cs[index] = (VertexIndex) _newM->vert.size();
00543 pos = _y_cs[index];
00544 Allocator<NewMeshType>::AddVertices( *_newM, 1);
00545 v = &_newM->vert[ pos ];
00546 v->P()=Interpolate(p1,p2,1);
00547 }
00548 assert(pos>=0);
00549 v = &_newM->vert[pos];
00550 }
00551
00553 void GetZIntercept(const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
00554 {
00555 assert(p1.X() == p2.X());
00556 assert(p1.Y() == p2.Y());
00557 assert(p1.Z()+1 == p2.Z());
00558
00559 int i = p1.X();
00560 int z = p1.Z();
00561 VertexIndex index = i+z*this->siz.X();
00562
00563 VertexIndex pos=-1;
00564 if (p1.Y()==CurrentSlice)
00565 {
00566 if ((pos=_z_cs[index])==-1)
00567 {
00568 _z_cs[index] = (VertexIndex) _newM->vert.size();
00569 pos = _z_cs[index];
00570 Allocator<NewMeshType>::AddVertices( *_newM, 1 );
00571 v = &_newM->vert[pos];
00572 v->P()=Interpolate(p1,p2,2);
00573 return;
00574 }
00575 }
00576 if (p1.Y()==CurrentSlice+1)
00577 {
00578 if ((pos=_z_ns[index])==-1)
00579 {
00580 _z_ns[index] = (VertexIndex) _newM->vert.size();
00581 pos = _z_ns[index];
00582 Allocator<NewMeshType>::AddVertices( *_newM, 1 );
00583 v = &_newM->vert[pos];
00584 v->P()=Interpolate(p1,p2,2);
00585 return;
00586 }
00587 }
00588 assert(pos>=0);
00589 v = &_newM->vert[pos];
00590 }
00591
00592 };
00593
00594 public:
00595
00596 typedef Walker MyWalker;
00597
00598 typedef vcg::tri::MarchingCubes<NewMeshType, MyWalker> MyMarchingCubes;
00599
00601 static void Resample(OldMeshType &old_mesh, NewMeshType &new_mesh, NewBoxType volumeBox, vcg::Point3<int> accuracy,float max_dist, float thr=0, bool DiscretizeFlag=false, bool MultiSampleFlag=false, bool AbsDistFlag=false, vcg::CallBackPos *cb=0 )
00602 {
00604 vcg::tri::UpdateBounding<OldMeshType>::Box(old_mesh);
00605
00606 MyWalker walker(volumeBox,accuracy);
00607
00608 walker.max_dim=max_dist+fabs(thr);
00609 walker.offset = - thr;
00610 walker.DiscretizeFlag = DiscretizeFlag;
00611 walker.MultiSampleFlag = MultiSampleFlag;
00612 walker.AbsDistFlag = AbsDistFlag;
00613 MyMarchingCubes mc(new_mesh, walker);
00614 walker.BuildMesh(old_mesh,new_mesh,mc,cb);
00615 }
00616
00617
00618 };
00619
00620 }
00621 }
00622 #endif