Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 #ifndef __VCG_DECIMATION_COLLAPSE
00028 #define __VCG_DECIMATION_COLLAPSE
00029
00030 #include<vcg/complex/algorithms/local_optimization.h>
00031 #include<vcg/simplex/tetrahedron/pos.h>
00032 #include<vcg/complex/tetramesh/edge_collapse.h>
00033 #include<vcg/space/point3.h>
00034
00035
00036 struct FAIL{
00037 static int VOL(){static int vol=0; return vol++;}
00038 static int LKF(){static int lkf=0; return lkf++;}
00039 static int LKE(){static int lke=0; return lke++;}
00040 static int LKV(){static int lkv=0; return lkv++;}
00041 static int OFD(){static int ofd=0; return ofd++;}
00042 static int BOR(){static int bor=0; return bor++;}
00043
00044 };
00045
00046 namespace vcg{
00047 namespace tetra{
00048
00051
00052
00053
00054
00055
00056 template<class TETRA_MESH_TYPE>
00057 class TetraEdgeCollapse: public LocalOptimization<TETRA_MESH_TYPE>::LocModType
00058 {
00059
00061
00063 typedef typename TETRA_MESH_TYPE::TetraType TetraType;
00065 typedef typename TetraType::VertexType VertexType;
00067 typedef typename TetraType::VertexType::CoordType CoordType;
00069 typedef typename TETRA_MESH_TYPE::VertexType::ScalarType ScalarType;
00071
00073 typedef Pos<TetraType> PosType;
00075 typedef PosLoop<TetraType> PosLType;
00077 typedef typename LocalOptimization<TETRA_MESH_TYPE>::HeapElem HeapElem;
00078 private:
00079
00081 Point3<ScalarType> _NewPoint;
00083 vcg::tetra::EdgeCollapse<TETRA_MESH_TYPE> _EC;
00085 static int& _Imark(){ static int im=0; return im;}
00087 PosType pos;
00089 VertexType *vrem;
00091 ScalarType _priority;
00092
00093 public:
00095 TetraEdgeCollapse()
00096 {}
00097
00099 TetraEdgeCollapse(PosType p,int mark)
00100 {
00101 _Imark() = mark;
00102 pos=p;
00103 _priority = _AspectRatioMedia(p);
00104 }
00105
00106 ~TetraEdgeCollapse()
00107 {}
00108
00109 private:
00110
00113 ScalarType _AspectRatioMedia(PosType p)
00114 {
00115 PosLType posl=PosLType(p.T(),p.F(),p.E(),p.V());
00116 posl.Reset();
00117 int num=0;
00118 ScalarType ratio_media=0.f;
00119 while(!posl.LoopEnd())
00120 {
00121 ratio_media+=posl.T()->AspectRatio();
00122 posl.NextT();
00123 num++;
00124 }
00125 ratio_media=ratio_media/num;
00126 return (ratio_media);
00127 }
00128
00129
00131 ScalarType _VolumePreservingError(PosType &pos,CoordType &new_point,int nsteps)
00132 {
00133 VertexType *ve0=(pos.T()->V(Tetra::VofE(pos.E(),0)));
00134 VertexType *ve1=(pos.T()->V(Tetra::VofE(pos.E(),1)));
00135 bool ext_v0=ve0->IsB();
00136 bool ext_v1=ve1->IsB();
00137
00138 ScalarType best_error=0.f;
00139 if ((ext_v0)&&(!ext_v1))
00140 new_point=ve0->P();
00141 else
00142 if ((!ext_v0)&&(ext_v1))
00143 new_point=ve1->P();
00144 else
00145 if ((!ext_v0)&&(!ext_v1))
00146 {
00147
00148
00149
00150
00151 new_point=(ve0->cP()+ve1->cP())/2.f;
00152 }
00153 else
00154 if ((ext_v0)&&(ext_v1))
00155 {
00156 ScalarType step=1.f/(nsteps-1);
00157 ScalarType Vol_Original=_EC.VolumeOriginal();
00158 for (int i=0;i<nsteps;i++)
00159 {
00160 best_error=1000000.f;
00161 ScalarType alfatemp=step*((ScalarType)i);
00162
00163
00164
00165
00166
00167 CoordType newPTemp=(ve0->cP()*alfatemp) +(ve1->cP()*(1.f-alfatemp));
00168
00169 ScalarType error=fabs(Vol_Original-_EC.VolumeSimulateCollapse(pos,newPTemp));
00170 if(error<best_error)
00171 {
00172 new_point=newPTemp;
00173 best_error=error;
00174 }
00175 }
00176 }
00177 return (best_error);
00178 }
00179
00180
00181
00182 public:
00183
00184 virtual const char *Info(TETRA_MESH_TYPE &m) {
00185 static char buf[60];
00186
00187 return buf;
00188 }
00189
00190 ScalarType ComputePriority()
00191 {
00192 return (_priority = _AspectRatioMedia(this->pos));
00193 }
00194
00195 ScalarType ComputeError()
00196 {
00197 vrem=(pos.T()->V(Tetra::VofE(pos.E(),0)));
00198 return (_VolumePreservingError(pos,_NewPoint,5));
00199 }
00200
00201 void Execute(TETRA_MESH_TYPE &tm)
00202 {
00203
00204 assert(!vrem->IsD());
00205 int del=_EC.DoCollapse(pos,_NewPoint);
00206 tm.tn-=del;
00207 tm.vn-=1;
00208 }
00209
00210 void UpdateHeap(typename LocalOptimization<TETRA_MESH_TYPE>::HeapType & h_ret)
00211 {
00212 assert(!vrem->IsD());
00213 _Imark()++;
00214 VTIterator<TetraType> VTi(vrem->VTb(),vrem->VTi());
00215 while (!VTi.End())
00216 {
00217 VTi.Vt()->ComputeVolume();
00218 for (int j=0;j<6;j++)
00219 {
00220 vcg::tetra::Pos<TetraType> p=Pos<TetraType>(VTi.Vt(),Tetra::FofE(j,0),j,Tetra::VofE(j,0));
00221 assert(!p.T()->V(p.V())->IsD());
00222 assert(!p.T()->IsD());
00223 h_ret.push_back(HeapElem(new TetraEdgeCollapse<TETRA_MESH_TYPE>(p,_Imark())));
00224 std::push_heap(h_ret.begin(),h_ret.end());
00225
00226 VTi.Vt()->V(Tetra::VofE(j,0))->IMark() = _Imark();
00227 }
00228 ++VTi;
00229 }
00230 }
00231
00233
00234 ModifierType IsOfType(){ return TetraEdgeCollapseOp;}
00235
00236 bool IsFeasible(){
00237 vcg::tetra::EdgeCollapse<TETRA_MESH_TYPE>::Reset();
00238 _EC.FindSets(pos);
00239 ComputeError();
00240 return(_EC.CheckPreconditions(pos,_NewPoint));
00241 }
00242
00243 bool IsUpToDate(){
00244 if (!pos.T()->IsD())
00245 {
00246 VertexType *v0=pos.T()->V(Tetra::VofE(pos.E(),0));
00247 VertexType *v1=pos.T()->V(Tetra::VofE(pos.E(),1));
00248 assert(!v0->IsD());
00249 assert(!v1->IsD());
00250 if(! (( (!v0->IsD()) && (!v1->IsD())) &&
00251 _Imark()>=v0->IMark() &&
00252 _Imark()>=v1->IMark()))
00253 {
00254 FAIL::OFD();
00255 return false;
00256 }
00257 else
00258 return true;
00259 }
00260 else
00261 return false;
00262 }
00263
00264 virtual ScalarType Priority() const {
00265 return _priority;
00266 }
00267
00269 static void Init(TETRA_MESH_TYPE &m,typename LocalOptimization<TETRA_MESH_TYPE>::HeapType& h_ret){
00270 h_ret.clear();
00271 typename TETRA_MESH_TYPE::TetraIterator ti;
00272 for(ti = m.tetra.begin(); ti != m.tetra.end();++ti)
00273 if(!(*ti).IsD()){
00274 (*ti).ComputeVolume();
00275 for (int j=0;j<6;j++)
00276 {
00277 PosType p=PosType(&*ti,Tetra::FofE(j,0),j,Tetra::VofE(j,0));
00278 assert(!p.T()->V(p.V())->IsD());
00279 assert(!p.T()->IsD());
00280 h_ret.push_back(HeapElem(new TetraEdgeCollapse<TETRA_MESH_TYPE>(p,m.IMark)));
00281 }
00282 }
00283 }
00284
00285 };
00286 }
00287 }
00288 #endif