00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include<vcg/space/plane3.h>
00025 #include<vcg/space/segment3.h>
00026 #include<vcg/space/intersection3.h>
00027 #include<vcg/complex/complex.h>
00028 #include<vcg/complex/algorithms/closest.h>
00029 #include<vcg/complex/algorithms/update/quality.h>
00030 #include<vcg/complex/algorithms/update/selection.h>
00031
00032
00033 #ifndef __VCGLIB_INTERSECTION_TRI_MESH
00034 #define __VCGLIB_INTERSECTION_TRI_MESH
00035
00036 namespace vcg{
00037
00038
00039
00040
00041
00047 template < typename GridType,typename ScalarType>
00048 bool IntersectionPlaneGrid( GridType & grid, Plane3<ScalarType> plane, std::vector<typename GridType::Cell *> &cells)
00049 {
00050 cells.clear();
00051 Point3d p,_d;
00052 Plane3d pl;
00053 _d.Import(plane.Direction());
00054 pl.SetDirection(_d);
00055 pl.SetOffset(plane.Offset());
00056 for( int ax = 0; ax <3; ++ax)
00057 { int axis = ax;
00058 int axis0 = (axis+1)%3;
00059 int axis1 = (axis+2)%3;
00060 int i,j;
00061 Point3i pi;
00062
00063 Segment3<double> seg;
00064 seg.P0().Import(grid.bbox.min);
00065 seg.P1().Import(grid.bbox.min);
00066 seg.P1()[axis] = grid.bbox.max[axis];
00067
00068 for(i = 0 ; i <= grid.siz[axis0]; ++i){
00069 for(j = 0 ; j <= grid.siz[axis1]; ++j)
00070 {
00071 seg.P0()[axis0] = grid.bbox.min[axis0]+ (i+0.01) * grid.voxel[axis0] ;
00072 seg.P1()[axis0] = grid.bbox.min[axis0]+ (i+0.01) * grid.voxel[axis0];
00073 seg.P0()[axis1] = grid.bbox.min[axis1]+ (j+0.01) * grid.voxel[axis1];
00074 seg.P1()[axis1] = grid.bbox.min[axis1]+ (j+0.01) * grid.voxel[axis1];
00075 if ( IntersectionPlaneSegmentEpsilon(pl,seg,p))
00076 {
00077 pi[axis] = std::min(std::max(0,(int)floor((p[axis ]-grid.bbox.min[axis])/grid.voxel[axis])),grid.siz[axis]);
00078 pi[axis0] = i;
00079 pi[axis1] = j;
00080 grid.Grid(pi,axis,cells);
00081 }
00082 }
00083 }
00084 }
00085 sort(cells.begin(),cells.end());
00086 cells.erase(unique(cells.begin(),cells.end()),cells.end());
00087
00088 return false;
00089 }
00090
00105 template < typename TriMeshType, typename EdgeMeshType, class ScalarType >
00106 bool IntersectionPlaneMeshOld(TriMeshType & m,
00107 Plane3<ScalarType> pl,
00108 EdgeMeshType & em)
00109 {
00110 typename EdgeMeshType::VertexIterator vi;
00111 typename TriMeshType::FaceIterator fi;
00112 em.Clear();
00113 Segment3<ScalarType> seg;
00114 for(fi=m.face.begin();fi!=m.face.end();++fi)
00115 if(!(*fi).IsD())
00116 {
00117 if(vcg::IntersectionPlaneTriangle(pl,*fi,seg))
00118 {
00119 vcg::tri::Allocator<EdgeMeshType>::AddEdges(em,1);
00120 vi = vcg::tri::Allocator<EdgeMeshType>::AddVertices(em,2);
00121 (*vi).P() = seg.P0();
00122 em.edge.back().V(0) = &(*vi);
00123 vi++;
00124 (*vi).P() = seg.P1();
00125 em.edge.back().V(1) = &(*vi);
00126 }
00127 }
00128
00129 return true;
00130 }
00131
00140 template < typename TriMeshType, typename EdgeMeshType, class ScalarType >
00141 bool IntersectionPlaneMesh(TriMeshType & m,
00142 Plane3<ScalarType> pl,
00143 EdgeMeshType & em)
00144 {
00145 std::vector<Point3<ScalarType> > ptVec;
00146 std::vector<Point3<ScalarType> > nmVec;
00147
00148 typename TriMeshType::template PerVertexAttributeHandle < ScalarType > qH =
00149 tri::Allocator<TriMeshType> :: template AddPerVertexAttribute < ScalarType >(m,"TemporaryPlaneDistance");
00150
00151 typename TriMeshType::VertexIterator vi;
00152 for(vi=m.vert.begin();vi!=m.vert.end();++vi) if(!(*vi).IsD())
00153 qH[vi] =SignedDistancePlanePoint(pl,(*vi).cP());
00154
00155 for(size_t i=0;i<m.face.size();i++)
00156 if(!m.face[i].IsD())
00157 {
00158 ptVec.clear();
00159 nmVec.clear();
00160 for(int j=0;j<3;++j)
00161 {
00162 if((qH[m.face[i].V0(j)] * qH[m.face[i].V1(j)])<0)
00163 {
00164 const Point3<ScalarType> &p0 = m.face[i].V0(j)->cP();
00165 const Point3<ScalarType> &p1 = m.face[i].V1(j)->cP();
00166 const Point3<ScalarType> &n0 = m.face[i].V0(j)->cN();
00167 const Point3<ScalarType> &n1 = m.face[i].V1(j)->cN();
00168 float q0 = qH[m.face[i].V0(j)];
00169 float q1 = qH[m.face[i].V1(j)];
00170
00171 Point3<ScalarType> pp;
00172 Segment3<ScalarType> seg(p0,p1);
00173 IntersectionPlaneSegment(pl,seg,pp);
00174 ptVec.push_back(pp);
00175 Point3<ScalarType> nn =(n0*fabs(q1) + n1*fabs(q0))/fabs(q0-q1);
00176 nmVec.push_back(nn);
00177 }
00178 if (qH[m.face[i].V(j)] == 0)
00179 {
00180 ptVec.push_back(m.face[i].V(j)->cP());
00181 nmVec.push_back(m.face[i].V(j)->cN());
00182 }
00183 }
00184 if(ptVec.size()>=2)
00185 {
00186 typename EdgeMeshType::VertexIterator vi;
00187 vcg::tri::Allocator<EdgeMeshType>::AddEdges(em,1);
00188 vi = vcg::tri::Allocator<EdgeMeshType>::AddVertices(em,2);
00189 (*vi).P() = ptVec[0];
00190 (*vi).N() = nmVec[0];
00191 em.edge.back().V(0) = &(*vi);
00192 vi++;
00193 (*vi).P() = ptVec[1];
00194 (*vi).N() = nmVec[1];
00195 em.edge.back().V(1) = &(*vi);
00196 }
00197 }
00198 tri::Allocator<TriMeshType> :: template DeletePerVertexAttribute < ScalarType >(m,qH);
00199
00200 return true;
00201 }
00202
00203
00211 template < typename TriMeshType, class ScalarType, class IndexingType >
00212 bool Intersection(Plane3<ScalarType> pl,
00213 IndexingType *grid,
00214 typename std::vector<typename TriMeshType::FaceType*> &v)
00215 {
00216 typedef IndexingType GridType;
00217 typename TriMeshType::FaceIterator fi;
00218 v.clear();
00219 typename std::vector< typename GridType::Cell* > cells;
00220 Intersect(*grid,pl,cells);
00221 typename std::vector<typename GridType::Cell*>::iterator ic;
00222 typename GridType::Cell fs,ls;
00223
00224 for(ic = cells.begin(); ic != cells.end();++ic)
00225 {
00226 grid->Grid(*ic,fs,ls);
00227 typename GridType::Link * lk = fs;
00228 while(lk != ls){
00229 typename TriMeshType::FaceType & face = *(lk->Elem());
00230 v.push_back(&face);
00231 lk++;
00232 }
00233 }
00234 return true;
00235 }
00236
00240 template < typename TriMeshType, class ScalarType>
00241 bool IntersectionRayMesh(
00242 TriMeshType * m,
00243 const Line3<ScalarType> & ray,
00244 Point3<ScalarType> & hitPoint)
00245 {
00246
00247 typename TriMeshType::FaceIterator fi;
00248 bool hit=false;
00249
00250 if(m==0) return false;
00251
00252
00253
00254
00255 ScalarType bar1,bar2,dist;
00256 Point3<ScalarType> p1;
00257 Point3<ScalarType> p2;
00258 Point3<ScalarType> p3;
00259 for(fi = m->face.begin(); fi != m->face.end(); ++fi)
00260 {
00261 p1=vcg::Point3<ScalarType>( (*fi).P(0).X() ,(*fi).P(0).Y(),(*fi).P(0).Z() );
00262 p2=vcg::Point3<ScalarType>( (*fi).P(1).X() ,(*fi).P(1).Y(),(*fi).P(1).Z() );
00263 p3=vcg::Point3<ScalarType>( (*fi).P(2).X() ,(*fi).P(2).Y(),(*fi).P(2).Z() );
00264 if(IntersectionLineTriangle<ScalarType>(ray,p1,p2,p3,dist,bar1,bar2))
00265 {
00266 hitPoint= p1*(1-bar1-bar2) + p2*bar1 + p3*bar2;
00267 hit=true;
00268 }
00269 }
00270
00271 return hit;
00272 }
00273
00278 template < typename TriMeshType, class ScalarType>
00279 bool IntersectionRayMesh(
00280 TriMeshType * m,
00281 const Line3<ScalarType> & ray,
00282 Point3<ScalarType> & hitPoint,
00283 ScalarType &bar1,
00284 ScalarType &bar2,
00285 ScalarType &bar3,
00286 typename TriMeshType::FacePointer fp
00287 )
00288 {
00289
00290 typename TriMeshType::FaceIterator fi;
00291 bool hit=false;
00292
00293 if(m==0) return false;
00294
00295
00296
00297
00298 ScalarType dist;
00299 Point3<ScalarType> p1;
00300 Point3<ScalarType> p2;
00301 Point3<ScalarType> p3;
00302 for(fi = m->face.begin(); fi != m->face.end(); ++fi)
00303 {
00304 p1=vcg::Point3<ScalarType>( (*fi).P(0).X() ,(*fi).P(0).Y(),(*fi).P(0).Z() );
00305 p2=vcg::Point3<ScalarType>( (*fi).P(1).X() ,(*fi).P(1).Y(),(*fi).P(1).Z() );
00306 p3=vcg::Point3<ScalarType>( (*fi).P(2).X() ,(*fi).P(2).Y(),(*fi).P(2).Z() );
00307 if(IntersectionLineTriangle<ScalarType>(ray,p1,p2,p3,dist,bar1,bar2))
00308 {
00309 bar3 = (1-bar1-bar2);
00310 hitPoint= p1*bar3 + p2*bar1 + p3*bar2;
00311 fp = &(*fi);
00312 hit=true;
00313 }
00314 }
00315
00316 return hit;
00317 }
00318
00327 template < typename TriMeshType, class ScalarType>
00328 void IntersectionBallMesh( TriMeshType & m, const vcg::Sphere3<ScalarType> &ball, TriMeshType & res,
00329 float tol = 0){
00330
00331 typename TriMeshType::VertexIterator v0,v1,v2;
00332 typename TriMeshType::FaceIterator fi;
00333 std::vector<typename TriMeshType:: FaceType*> closests;
00334 vcg::Point3<ScalarType> witness;
00335 std::pair<ScalarType, ScalarType> info;
00336
00337 if(tol == 0) tol = M_PI * ball.Radius() * ball.Radius() / 100000;
00338 tri::UpdateSelection<TriMeshType>::FaceClear(m);
00339 for(fi = m.face.begin(); fi != m.face.end(); ++fi)
00340 if(!(*fi).IsD() && IntersectionSphereTriangle<ScalarType>(ball ,(*fi), witness , &info))
00341 (*fi).SetS();
00342
00343 res.Clear();
00344 tri::Append<TriMeshType,TriMeshType>::Selected(res,m);
00345 int i =0;
00346 while(i<res.fn){
00347 bool allIn = ( ball.IsIn(res.face[i].P(0)) && ball.IsIn(res.face[i].P(1))&&ball.IsIn(res.face[i].P(2)));
00348 if( IntersectionSphereTriangle<ScalarType>(ball ,res.face[i], witness , &info) && !allIn){
00349 if(vcg::DoubleArea(res.face[i]) > tol)
00350 {
00351
00352 v0 = vcg::tri::Allocator<TriMeshType>::AddVertices(res,3);
00353 fi = vcg::tri::Allocator<TriMeshType>::AddFaces(res,4);
00354
00355 v1 = v0; ++v1;
00356 v2 = v1; ++v2;
00357 (*v0).P() = (res.face[i].P(0) + res.face[i].P(1))*0.5;
00358 (*v1).P() = (res.face[i].P(1) + res.face[i].P(2))*0.5;
00359 (*v2).P() = (res.face[i].P(2) + res.face[i].P(0))*0.5;
00360
00361 (*fi).V(0) = res.face[i].V(0);
00362 (*fi).V(1) = &(*v0);
00363 (*fi).V(2) = &(*v2);
00364 ++fi;
00365
00366 (*fi).V(0) = res.face[i].V(1);
00367 (*fi).V(1) = &(*v1);
00368 (*fi).V(2) = &(*v0);
00369 ++fi;
00370
00371 (*fi).V(0) = &(*v0);
00372 (*fi).V(1) = &(*v1);
00373 (*fi).V(2) = &(*v2);
00374 ++fi;
00375
00376 (*fi).V(0) = &(*v2);
00377 (*fi).V(1) = &(*v1);
00378 (*fi).V(2) = res.face[i].V(2) ;
00379
00380 vcg::tri::Allocator<TriMeshType>::DeleteFace(res,res.face[i]);
00381 }
00382 }
00383
00384 if(info.first > 0.0)
00385 vcg::tri::Allocator<TriMeshType>::DeleteFace(res,res.face[i]);
00386 ++i;
00387 }
00388 }
00389
00390
00391 template < typename TriMeshType, class ScalarType, class IndexingType>
00392 void IntersectionBallMesh( IndexingType * grid, TriMeshType & m, const vcg::Sphere3<ScalarType> &ball, TriMeshType & res,
00393 float tol = 0){
00394
00395 typename TriMeshType::VertexIterator v0,v1,v2;
00396 typename std::vector<typename TriMeshType::FacePointer >::iterator cfi;
00397 typename TriMeshType::FaceIterator fi;
00398 std::vector<typename TriMeshType:: FaceType*> closestsF,closests;
00399 vcg::Point3<ScalarType> witness;
00400 std::vector<vcg::Point3<ScalarType> > witnesses;
00401 std::vector<ScalarType> distances;
00402 std::pair<ScalarType, ScalarType> info;
00403
00404 if(tol == 0) tol = M_PI * ball.Radius() * ball.Radius() / 100000;
00405
00406 vcg::tri::GetInSphereFaceBase(m,*grid, ball.Center(), ball.Radius(),closestsF,distances,witnesses);
00407 for(cfi =closestsF.begin(); cfi != closestsF.end(); ++cfi)
00408 if(!(**cfi).IsD() && IntersectionSphereTriangle<ScalarType>(ball ,(**cfi), witness , &info))
00409 closests.push_back(&(**cfi));
00410
00411 res.Clear();
00412 SubSet(res,closests);
00413 int i =0;
00414 while(i<res.fn){
00415 bool allIn = ( ball.IsIn(res.face[i].P(0)) && ball.IsIn(res.face[i].P(1))&&ball.IsIn(res.face[i].P(2)));
00416 if( IntersectionSphereTriangle<ScalarType>(ball ,res.face[i], witness , &info) && !allIn){
00417 if(vcg::DoubleArea(res.face[i]) > tol)
00418 {
00419
00420 v0 = vcg::tri::Allocator<TriMeshType>::AddVertices(res,3);
00421 fi = vcg::tri::Allocator<TriMeshType>::AddFaces(res,4);
00422
00423 v1 = v0; ++v1;
00424 v2 = v1; ++v2;
00425 (*v0).P() = (res.face[i].P(0) + res.face[i].P(1))*0.5;
00426 (*v1).P() = (res.face[i].P(1) + res.face[i].P(2))*0.5;
00427 (*v2).P() = (res.face[i].P(2) + res.face[i].P(0))*0.5;
00428
00429 (*fi).V(0) = res.face[i].V(0);
00430 (*fi).V(1) = &(*v0);
00431 (*fi).V(2) = &(*v2);
00432 ++fi;
00433
00434 (*fi).V(0) = res.face[i].V(1);
00435 (*fi).V(1) = &(*v1);
00436 (*fi).V(2) = &(*v0);
00437 ++fi;
00438
00439 (*fi).V(0) = &(*v0);
00440 (*fi).V(1) = &(*v1);
00441 (*fi).V(2) = &(*v2);
00442 ++fi;
00443
00444 (*fi).V(0) = &(*v2);
00445 (*fi).V(1) = &(*v1);
00446 (*fi).V(2) = res.face[i].V(2) ;
00447
00448 vcg::tri::Allocator<TriMeshType>::DeleteFace(res,res.face[i]);
00449 }
00450 }
00451
00452 if(info.first > 0.0)
00453 vcg::tri::Allocator<TriMeshType>::DeleteFace(res,res.face[i]);
00454 ++i;
00455 }
00456 }
00457
00459 }
00460 #endif