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
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053 #ifndef LASS_GUARDIAN_OF_INCLUSION_SPAT_PLANAR_MESH_H
00054 #define LASS_GUARDIAN_OF_INCLUSION_SPAT_PLANAR_MESH_H
00055
00056 #include "spat_common.h"
00057 #include "quad_edge.h"
00058 #include "../prim/point_2d.h"
00059 #include "../prim/aabb_2d.h"
00060 #include "../prim/ray_2d.h"
00061 #include "../prim/line_2d.h"
00062 #include "../prim/line_segment_2d.h"
00063 #include "../prim/simple_polygon_2d.h"
00064 #include "../prim/triangle_2d.h"
00065 #include "../prim/side.h"
00066 #include "../util/callback_r_1.h"
00067 #include "../util/callback_r_2.h"
00068 #include "../util/callback_r_3.h"
00069 #include "../io/matlab_o_stream.h"
00070 #include "../meta/tuple.h"
00071 #include "../stde/extended_iterator.h"
00072
00073 #define DEBUG_MESH 0
00074
00075 namespace lass
00076 {
00077 namespace spat
00078 {
00079 #define TEMPLATE_DEF template< \
00080 typename T, \
00081 typename PointHandle, \
00082 typename EdgeHandle, \
00083 typename FaceHandle >
00084
00085 namespace impl
00086 {
00087 TEMPLATE_DEF class EdgeToMatlab;
00088 TEMPLATE_DEF class EdgeGatherer;
00089 TEMPLATE_DEF class EdgeMarker;
00090 }
00091
00092 namespace experimental
00093 {
00094 struct ObjectAllocator:
00095 private util::AllocatorThrow<
00096 util::AllocatorBinned<
00097 util::AllocatorSimpleBlock<>, 512
00098 >
00099 >
00100 {
00101 template <typename T> T* const make(const T& x)
00102 {
00103 T* const p = static_cast<T*>(allocate(sizeof(T)));
00104 try
00105 {
00106 new (p) T(x);
00107 }
00108 catch (...)
00109 {
00110 deallocate(p, sizeof(T));
00111 throw;
00112 }
00113 return p;
00114 }
00115 template <typename T> void free(T* p)
00116 {
00117 if (p)
00118 {
00119 p->~T();
00120 deallocate(p, sizeof(T));
00121 }
00122 }
00123 };
00124
00125 template <typename T>
00126 class BitField
00127 {
00128 public:
00129 enum { size = 8 * sizeof(T) };
00130 BitField(T bits = 0x0): bits_(bits) {}
00131 const bool operator[](size_t i) const
00132 {
00133 return bits_ & mask(i) ? true : false;
00134 }
00135 void set(size_t i)
00136 {
00137 bits_ |= mask(i);
00138 }
00139 void set(size_t i, bool value)
00140 {
00141 const T m = mask(i);
00142 bits_ &= ~m;
00143 bits_ |= (value ? m : 0);
00144 }
00145 void unset(size_t i)
00146 {
00147 bits_ &= ~mask(i);
00148 }
00149 private:
00150 const T mask(size_t i) const
00151 {
00152 LASS_ASSERT(i < size);
00153 return 1 << i;
00154 }
00155 T bits_;
00156 };
00157
00158 template <typename T>
00159 class ResetableThreadLocalVariable
00160 {
00161 public:
00162 ResetableThreadLocalVariable(const T& proto = T()):
00163 proto_(proto)
00164 {
00165
00166 TTls* tls = reinterpret_cast<TTls*>(tls_);
00167 new (tls) TTls(Impl(this));
00168 }
00169 ~ResetableThreadLocalVariable()
00170 {
00171 TTls* tls = reinterpret_cast<TTls*>(tls_);
00172 tls->~TTls();
00173 }
00174 T& operator*()
00175 {
00176 return *(*reinterpret_cast<TTls*>(tls_))->it;
00177 }
00178 const T& operator*() const
00179 {
00180 return *(*reinterpret_cast<TTls*>(tls_))->it;
00181 }
00182 void reset(const T& proto)
00183 {
00184 LASS_LOCK(mutex_)
00185 {
00186 proto_ = proto;
00187 std::fill(values_.begin(), values_.end(), proto_);
00188 }
00189 }
00190 private:
00191 struct Impl
00192 {
00193 Impl(ResetableThreadLocalVariable* self): self(self)
00194 {
00195 self->registerImpl(this);
00196 }
00197 Impl(const Impl& other): self(other.self)
00198 {
00199 self->registerImpl(this);
00200 }
00201 ~Impl()
00202 {
00203 self->unregisterImpl(this);
00204 }
00205 ResetableThreadLocalVariable* self;
00206 typename std::list<T>::iterator it;
00207 };
00208
00209 typedef util::ThreadLocalVariable<Impl> TTls;
00210
00211 void registerImpl(Impl* impl)
00212 {
00213 LASS_LOCK(mutex_)
00214 {
00215 values_.push_back(proto_);
00216 impl->it = stde::prev(values_.end());
00217 }
00218 }
00219 void unregisterImpl(Impl* impl)
00220 {
00221 LASS_LOCK(mutex_)
00222 {
00223 values_.erase(impl->it);
00224 }
00225 }
00226
00227 char tls_[sizeof(TTls)];
00228 std::list<T> values_;
00229 T proto_;
00230 util::Semaphore mutex_;
00231 };
00232
00233 }
00234
00235 TEMPLATE_DEF
00236 class PlanarMesh: private experimental::ObjectAllocator
00237 {
00238 public:
00239 typedef lass::prim::Point2D<T> TPoint2D;
00240 typedef lass::prim::Vector2D<T> TVector2D;
00241 typedef lass::prim::Line2D<T, prim::Cartesian, prim::Unnormalized > TLine2D;
00242 typedef lass::prim::Ray2D<T, prim::Unnormalized, prim::Unbounded > TRay2D;
00243 typedef lass::prim::LineSegment2D<T> TLineSegment2D;
00244 typedef lass::prim::SimplePolygon2D<T> TSimplePolygon2D;
00245 typedef lass::prim::Triangle2D<T> TTriangle2D;
00246 typedef experimental::BitField<num::Tuint32> TBitField;
00247
00248 static const int PLANAR_MESH_STACK_DEPTH = TBitField::size - 1;
00249 enum
00250 {
00251 stackDepth = TBitField::size - 1,
00252 publicMarkIndex = TBitField::size - 1
00253 };
00254 private:
00255 struct ProxyHandle: private meta::Tuple< typename meta::type_list::Make<PointHandle, EdgeHandle, FaceHandle>::Type >
00256 {
00257 typedef meta::Tuple< typename meta::type_list::Make<PointHandle, EdgeHandle, FaceHandle>::Type > THandles;
00258
00259 TPoint2D* point_;
00260 TBitField internalMark_;
00261
00262 ProxyHandle(): point_(NULL), internalMark_(0x00) {}
00263 const PointHandle& pointHandle() const { return meta::tuple::field<0>(static_cast<const THandles&>(*this)); }
00264 const EdgeHandle& edgeHandle() const { return meta::tuple::field<1>(static_cast<const THandles&>(*this)); }
00265 const FaceHandle& faceHandle() const { return meta::tuple::field<2>(static_cast<const THandles&>(*this)); }
00266 PointHandle& pointHandle() { return meta::tuple::field<0>(static_cast<THandles&>(*this)); }
00267 EdgeHandle& edgeHandle() { return meta::tuple::field<1>(static_cast<THandles&>(*this)); }
00268 FaceHandle& faceHandle() { return meta::tuple::field<2>(static_cast<THandles&>(*this)); }
00269 };
00270 class StackIncrementer
00271 {
00272 int* stackDepth_;
00273 int maxStackDepth_;
00274 StackIncrementer() {}
00275 public:
00276 StackIncrementer( int* iStackVar, int iMaxStackDepth ) : stackDepth_(iStackVar), maxStackDepth_( iMaxStackDepth )
00277 {
00278 ++(*stackDepth_);
00279 if (*stackDepth_>maxStackDepth_)
00280 {
00281 --(*stackDepth_);
00282 throw std::runtime_error("PlanarMesh: stack overflow");
00283 }
00284 }
00285 ~StackIncrementer()
00286 {
00287 --(*stackDepth_);
00288 }
00289 };
00290
00291 public:
00292 typedef lass::spat::QuadEdge<ProxyHandle> TQuadEdge;
00293 typedef typename TQuadEdge::Edge TEdge;
00294 typedef std::vector< TQuadEdge* > TQuadEdgeList;
00295 typedef std::vector< ProxyHandle* > TProxyHandleList;
00296 typedef lass::util::CallbackR1<bool,TEdge*> TEdgeCallback;
00297 typedef lass::util::CallbackR3<bool,TEdge*,const TSimplePolygon2D&, FaceHandle> TEdgePolyFaceHandleCallback;
00298
00299 public:
00300 PlanarMesh( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c);
00301 PlanarMesh( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c, const TPoint2D& d);
00302 PlanarMesh( const prim::Aabb2D<T>& iAabb );
00303 void setTolerance(const T& iTolerance) {tolerance_ = iTolerance;}
00304 const T& tolerance() { return tolerance_; }
00305 void setPointDistanceTolerance(const T& iPointDistanceTolerance) {pointDistanceTolerance_ = iPointDistanceTolerance;}
00306 const T& pointDistanceTolerance() { return pointDistanceTolerance_; }
00307 virtual ~PlanarMesh();
00308
00309 TEdge* startEdge() const;
00310 bool isBoundingPoint( const TPoint2D& iPoint) const;
00311
00312 bool forAllPrimaryEdges( const TEdgeCallback& iCallback );
00313 bool forAllPrimaryUndirectedEdges( const TEdgeCallback& iCallback );
00314 bool forAllPrimaryUndirectedEdgesCached( const TEdgeCallback& iCallback );
00315 bool forAllDualEdges( const TEdgeCallback& iCallback );
00316 bool forAllEdges( const TEdgeCallback& iCallback );
00317 bool forAllVertices( const TEdgeCallback& iCallback );
00318 bool forAllFaces( const TEdgeCallback& iCallback );
00319 bool forAllFacesCached( const TEdgeCallback& iCallback );
00320 template <typename InputPolygonIterator, typename InputFaceHandleIterator>
00321 bool forAllPolygonFaces( InputPolygonIterator iFirstPolygon, InputPolygonIterator iLastPolygon, InputFaceHandleIterator iFirstFaceHandle, const TEdgePolyFaceHandleCallback& iCallback );
00322
00323
00324 TEdge* locate( const TPoint2D& iPoint, TEdge* iHint=0 ) const;
00325 TEdge* pointLocate( const TPoint2D& iPoint ) const;
00326 TEdge* shoot( const TRay2D& iRay ) const;
00327 template <typename OutputIterator> OutputIterator walk( const TLineSegment2D& iSegment, OutputIterator oCrossedEdges ) const;
00328 template <typename OutputIterator> OutputIterator walkIntersections( const TLineSegment2D& iSegment, OutputIterator oIntersections ) const;
00329 std::pair<int, TEdge*> walkTillConstrained( const TRay2D& iRay) const;
00330 TEdge* insertSite( const TPoint2D& iPoint, bool makeDelaunay = true, bool forceOnEdge = false);
00331 TEdge* insertEdge( const TLineSegment2D& iSegment, EdgeHandle iLeftHandle = EdgeHandle(), EdgeHandle iRightHandle = EdgeHandle(), PointHandle iPointHandle = PointHandle(), bool forcePointHandle = false, bool makeDelaunay = true);
00332 TEdge* insertPolygon( const TSimplePolygon2D& iSegment, EdgeHandle iLeftHandle = EdgeHandle(), EdgeHandle iRightHandle = EdgeHandle(), bool makeDelaunay = true);
00333 void markPolygon( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle );
00334 template <typename InputPolygonIterator, typename InputFaceHandleIterator>
00335 void markPolygons( InputPolygonIterator iFirstPolygon, InputPolygonIterator iLastPolygon, InputFaceHandleIterator iFirstFaceHandle);
00336 void markPolygons( const std::vector<TSimplePolygon2D>& iPolygons, const std::vector<FaceHandle>& iFaceHandles);
00337 bool deleteEdge( TEdge* iEdge );
00338 bool gcDeleteEdge( TEdge* iEdge );
00339 int gc();
00340 long edgeCount() const { return edgeCount_; }
00341 void makeMaximalConvexPolygon(T iMaxSurface=T(-1));
00342 void makeRectangular(T minAngle, T maxAngle);
00343
00344 static TTriangle2D triangle( const TEdge* iEdge);
00345 static TSimplePolygon2D polygon( const TEdge* iEdge);
00346 static const TPoint2D& org( const TEdge* iEdge );
00347 static const TPoint2D& dest( const TEdge* iEdge );
00348 static const TPoint2D& fastOrg( const TEdge* iEdge );
00349 static const TPoint2D& fastDest( const TEdge* iEdge );
00350 static TPoint2D along( const TEdge* iEdge, const T& iParam );
00351 static TPoint2D fastAlong( const TEdge* iEdge, const T& iParam );
00352 static const TVector2D direction( const TEdge* iEdge );
00353 static bool rightOf( const TPoint2D& iPoint, const TEdge* iEdge );
00354 static bool fastRightOf( const TPoint2D& iPoint, const TEdge* iEdge );
00355 static bool leftOf( const TPoint2D& iPoint, const TEdge* iEdge );
00356 static bool fastLeftOf( const TPoint2D& iPoint, const TEdge* iEdge );
00357 static bool onEdge( const TPoint2D& iPoint, const TEdge* iEdge );
00358 static bool hasLeftFace( const TEdge* iEdge );
00359 static bool fastHasLeftFace( const TEdge* iEdge );
00360 static bool hasRightFace( const TEdge* iEdge );
00361 static int chainOrder( const TEdge* iEdge );
00362 static int vertexOrder( const TEdge* iEdge );
00363 static bool allEqualChainOrder( const TEdge* iEdge );
00364 static bool inConvexCell( const TPoint2D& iPoint, const TEdge* iEdge );
00365
00366
00367
00368 TEdge* makeEdge( const TPoint2D& a, const TPoint2D& b, bool makeConstrained );
00369 TEdge* connect( TEdge* a, TEdge* b );
00370 TEdge* split( TEdge* a, T iWhere );
00371 void swap( TEdge* iEdge );
00372
00373 void setTempQuadEdges(bool iAllocateInTemp);
00374
00375
00376
00377
00378
00379 static void setOrg( const TPoint2D& iOrg, TEdge* iEdge );
00380 static void setDest( const TPoint2D& iDest, TEdge* iEdge );
00381 bool moveWithinNeighbourhood( TEdge* iEdge, const TPoint2D& iNewLocation );
00382
00383
00384
00385
00386 #pragma LASS_TODO("Keep convexness constraint")
00387 bool removeVertex(TEdge* iEdge);
00388
00389 static bool inPrimaryMesh( const TEdge* iEdge );
00390 static bool inDualMesh( const TEdge* iEdge );
00391 static bool marking( const TEdge* iEdge );
00392 static void setMarking( TEdge* iEdge, bool iMark );
00393 static PointHandle pointHandle( const TEdge* iEdge );
00394 static EdgeHandle edgeHandle( const TEdge* iEdge );
00395 static FaceHandle faceHandle( const TEdge* iEdge );
00396 static PointHandle& pointHandleRef( TEdge* iEdge );
00397 static EdgeHandle& edgeHandleRef( TEdge* iEdge );
00398 static FaceHandle& faceHandleRef( TEdge* iEdge );
00399 static void setPointHandle( TEdge* iEdge, PointHandle iHandle );
00400 static void setEdgeHandle( TEdge* iEdge, EdgeHandle iHandle );
00401 static void setFaceHandle( TEdge* iEdge, FaceHandle iHandle );
00402 static void setOrientedEdgeHandle( TEdge* iEdge, EdgeHandle iLeftHandle, EdgeHandle iRightHandle, const TVector2D& iDirection );
00403 private:
00404 bool allocateInTemp_;
00405 TEdge* startEdge_;
00406 TQuadEdgeList quadEdgeList_;
00407 TQuadEdgeList tempQuadEdgeList_;
00408 std::vector<TPoint2D> boundingPoints_;
00409 T tolerance_;
00410 T pointDistanceTolerance_;
00411 long edgeCount_;
00412 int stackDepth_;
00413
00414
00415 mutable experimental::ResetableThreadLocalVariable<TEdge*> lastLocateEdge_;
00416 mutable experimental::ResetableThreadLocalVariable<TEdge*> lastFloodEdge_;
00417
00418 private:
00419 PlanarMesh();
00420 void init4( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c, const TPoint2D& d);
00421 void fixEdge( TEdge* e );
00422 TEdge* makeEmptyEdge( bool makeConstrained );
00423 void triangulate( TEdge* iEdge );
00424 void splitEdge(TEdge *e, const TPoint2D& iPoint );
00425 TEdge* pointShoot( const TRay2D& iRay ) const;
00426 template <typename OutputIterator> OutputIterator pointWalk( const TLineSegment2D& iSegment, OutputIterator oCrossedEdges ) const;
00427 void safeSplitEdge(TEdge *e, const TPoint2D& iPoint );
00428 TPoint2D snap(const TPoint2D& a, const TPoint2D& b, const TPoint2D& c);
00429
00430 TEdge* bruteForceLocate( const TPoint2D& iPoint ) const;
00431 TEdge* bruteForceExactLocate( const TPoint2D& iPoint ) const;
00432
00433 friend class impl::EdgeToMatlab<T, PointHandle, EdgeHandle, FaceHandle>;
00434 friend class impl::EdgeGatherer<T, PointHandle, EdgeHandle, FaceHandle>;
00435 friend class impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle>;
00436
00437 bool internalMarking( const TEdge* iEdge );
00438 bool deletePoint( TEdge* e);
00439 void setInternalMarking( TEdge* iEdge, bool iMark );
00440 void setInternalMarkingAroundVertex( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* iEdge, bool iMark );
00441 void setInternalMarkingInFace( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* iEdge, bool iMark );
00442
00443 bool floodPolygon( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle );
00444 bool floodPolygonCallback( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle, const TEdgePolyFaceHandleCallback& iCallback);
00445 #ifndef NDEBUG
00446 public:
00447 static unsigned numSetOrientedEdgeHandleCalls;
00448 static unsigned numSetOrientedEdgeHandleSwaps;
00449 #endif
00450 };
00451
00452 namespace impl
00453 {
00454
00455
00456
00457
00458 template <typename T>
00459 lass::prim::Result fastIntersect( const lass::prim::Point2D<T>& iA, const lass::prim::Point2D<T>& iB,
00460 const lass::prim::Point2D<T>& iC, const lass::prim::Point2D<T>& iD, lass::prim::Point2D<T>& oP)
00461 {
00462 typedef lass::num::NumTraits<T> TNumTraits;
00463 const lass::prim::Vector2D<T> dirA=iB-iA;
00464 const lass::prim::Vector2D<T> difference=iC-iA;
00465 const lass::prim::Vector2D<T> dirB=iD-iC;
00466
00467 const T denominator = lass::prim::perpDot(dirA, dirB);
00468 const T denominator2= denominator*2.0;
00469 oP = iA;
00470 if (denominator == denominator2)
00471 {
00472
00473
00474 return lass::prim::rInvalid;
00475 }
00476 else
00477 {
00478 const T oTa = perpDot(difference, dirB) / denominator;
00479 oP.x += dirA.x*oTa;
00480 oP.y += dirA.y*oTa;
00481 return lass::prim::rOne;
00482 }
00483 }
00484
00485 TEMPLATE_DEF
00486 class EdgeMarker
00487 {
00488 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00489 TPlanarMesh* mesh_;
00490 bool marking_;
00491 public:
00492 EdgeMarker( TPlanarMesh* iMesh, bool iMark ) : mesh_(iMesh), marking_(iMark) {}
00493
00494
00495 bool internalMark( typename TPlanarMesh::TEdge* e )
00496 {
00497 mesh_->setInternalMarking( e, marking_ );
00498 return true;
00499 }
00500 bool mark( typename TPlanarMesh::TEdge* e )
00501 {
00502 TPlanarMesh::setMarking( e, marking_ );
00503 return true;
00504 }
00505
00506 };
00507
00508 TEMPLATE_DEF
00509 class EdgeToMatlab
00510 {
00511 public:
00512 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00513 private:
00514 TPlanarMesh* mesh_;
00515 lass::io::MatlabOStream& stream_;
00516 public:
00517 EdgeToMatlab( TPlanarMesh* iMesh, lass::io::MatlabOStream& ioOStream ) : mesh_(iMesh), stream_( ioOStream ) {}
00518 bool edgeToMatlab( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* iEdge )
00519 {
00520 if (!mesh_->internalMarking( iEdge ))
00521 {
00522 if (iEdge->isConstrained())
00523 stream_.setColor(lass::io::mcRed);
00524 else
00525 stream_.setColor(lass::io::mcBlack);
00526 stream_ << typename TPlanarMesh::TLineSegment2D(
00527 TPlanarMesh::org(iEdge), TPlanarMesh::dest(iEdge) );
00528 }
00529 else
00530 return true;
00531 mesh_->setInternalMarking( iEdge, true );
00532 mesh_->setInternalMarking( iEdge->sym(), true );
00533 return true;
00534 }
00535 bool vertexToMatlab( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* iEdge )
00536 {
00537 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00538 if ( !mesh_->internalMarking( iEdge ) )
00539 stream_ << TPlanarMesh::org(iEdge);
00540 else
00541 return true;
00542 mesh_->setInternalMarkingAroundVertex( iEdge, true );
00543 return true;
00544 }
00545 };
00546
00547 TEMPLATE_DEF
00548 class EdgeGatherer
00549 {
00550 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00551 TPlanarMesh* mesh_;
00552 T lastArea_;
00553 public:
00554 typedef std::list< typename TPlanarMesh::TEdge* > TEdgeList;
00555 TEdgeList edgeList;
00556 T angleConstraintMin;
00557 T angleConstraintMax;
00558 T maxSurface;
00559
00560 EdgeGatherer( TPlanarMesh* iMesh ) : mesh_(iMesh), lastArea_(0) {}
00561 virtual ~EdgeGatherer() {}
00562
00563 bool makeConvexPolygon( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* e )
00564 {
00565 LASS_ASSERT( TPlanarMesh::inPrimaryMesh( e ) );
00566 if ( mesh_->internalMarking( e ) || e->isConstrained())
00567 return true;
00568
00569 if ( prim::weakCcw( TPlanarMesh::org(e->dNext()), TPlanarMesh::dest(e), TPlanarMesh::dest(e->lNext()))
00570 && prim::weakCcw( TPlanarMesh::org(e->sym()->dNext()), TPlanarMesh::org(e), TPlanarMesh::dest(e->sym()->lNext())) )
00571 {
00572 T dArea = num::abs(prim::doubleTriangleArea( TPlanarMesh::org(e->dNext()), TPlanarMesh::dest(e), TPlanarMesh::dest(e->lNext())))
00573 + num::abs(prim::doubleTriangleArea( TPlanarMesh::org(e->sym()->dNext()), TPlanarMesh::org(e), TPlanarMesh::dest(e->sym()->lNext())));
00574 if (maxSurface>T(0))
00575 {
00576
00577 T leftArea = TPlanarMesh::polygon(e).area();
00578 T rightArea = TPlanarMesh::polygon(e->sym()).area();
00579 if (leftArea+rightArea>maxSurface)
00580 return true;
00581 }
00582 if (lastArea_ == T(0))
00583 {
00584 lastArea_ = dArea;
00585 edgeList.push_back( e );
00586 }
00587 else
00588 {
00589 if (dArea<lastArea_)
00590 {
00591 edgeList.push_front( e );
00592 lastArea_ = dArea;
00593 }
00594 else
00595 edgeList.push_back( e );
00596 }
00597 return false;
00598 }
00599 return true;
00600 }
00601 bool makeRectangular( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* e )
00602 {
00603 LASS_ASSERT( TPlanarMesh::inPrimaryMesh( e ) );
00604 if ( mesh_->internalMarking( e ) || e->isConstrained())
00605 return true;
00606
00607 if ( prim::ccw( TPlanarMesh::org(e->dNext()), TPlanarMesh::dest(e), TPlanarMesh::dest(e->lNext()))
00608 && prim::ccw( TPlanarMesh::org(e->sym()->dNext()), TPlanarMesh::org(e), TPlanarMesh::dest(e->sym()->lNext())) )
00609 {
00610
00611 typename TPlanarMesh::TVector2D v1 = TPlanarMesh::fastDest(e->lNext())-TPlanarMesh::fastDest(e);
00612 typename TPlanarMesh::TVector2D v2 = TPlanarMesh::fastOrg(e)-TPlanarMesh::fastDest(e->lNext());
00613 typename TPlanarMesh::TVector2D v3 = TPlanarMesh::fastDest(e->sym()->lNext())-TPlanarMesh::fastOrg(e);
00614 typename TPlanarMesh::TVector2D v4 = TPlanarMesh::fastDest(e)-TPlanarMesh::fastDest(e->sym()->lNext());
00615 v1.normalize();
00616 v2.normalize();
00617 v3.normalize();
00618 v4.normalize();
00619 T angle1 = lass::num::acos(lass::prim::dot( v1, v2));
00620 T angle2 = lass::num::acos(lass::prim::dot( v2, v3));
00621 T angle3 = lass::num::acos(lass::prim::dot( v3, v4));
00622 T angle4 = lass::num::acos(lass::prim::dot( v4, v1));
00623 if ( lass::num::abs(angle1)>angleConstraintMin
00624 && lass::num::abs(angle2)>angleConstraintMin
00625 && lass::num::abs(angle3)>angleConstraintMin
00626 && lass::num::abs(angle4)>angleConstraintMin
00627 && lass::num::abs(angle1)<=angleConstraintMax
00628 && lass::num::abs(angle2)<=angleConstraintMax
00629 && lass::num::abs(angle3)<=angleConstraintMax
00630 && lass::num::abs(angle4)<=angleConstraintMax )
00631 {
00632 edgeList.push_back( e );
00633
00634
00635
00636 return false;
00637 }
00638 }
00639 return true;
00640 }
00641 };
00642
00643 TEMPLATE_DEF
00644 class BrutePointExactLocator
00645 {
00646 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00647 typename TPlanarMesh::TPoint2D point_;
00648 public:
00649 typename TPlanarMesh::TEdge* edge;
00650 BrutePointExactLocator( const typename TPlanarMesh::TPoint2D& iPoint ) : point_(iPoint), edge(NULL) {}
00651 bool findPoint( typename TPlanarMesh::TEdge* e )
00652 {
00653 if (TPlanarMesh::org(e)==point_)
00654 {
00655 edge = e;
00656 return false;
00657 }
00658 return true;
00659 }
00660 };
00661
00662 TEMPLATE_DEF
00663 class BrutePointLocator
00664 {
00665 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00666 typename TPlanarMesh::TPoint2D point_;
00667 public:
00668 typename TPlanarMesh::TEdge* edge;
00669 BrutePointLocator( const typename TPlanarMesh::TPoint2D& iPoint ) : point_(iPoint), edge(NULL) {}
00670 bool findEdge( typename TPlanarMesh::TEdge* e )
00671 {
00672 typename TPlanarMesh::TEdge* ce = e;
00673 for (int i=0;i<3;++i)
00674 {
00675 if (TPlanarMesh::rightOf(point_,ce))
00676 return true;
00677 ce = ce->lNext();
00678 }
00679
00680 ce = e;
00681
00682 if (point_==TPlanarMesh::org(e))
00683 {
00684 edge = e;
00685 return false;
00686 }
00687 if (point_==TPlanarMesh::dest(e))
00688 {
00689 edge = e->sym();
00690 return false;
00691 }
00692 if (point_==TPlanarMesh::dest(e->lNext()))
00693 {
00694 edge = e->lNext()->sym();
00695 return false;
00696 }
00697
00698 typename TPlanarMesh::TRay2D R1(TPlanarMesh::org(e), TPlanarMesh::dest(e));
00699 typename TPlanarMesh::TPoint2D p1 = R1.point( R1.t( point_ ) );
00700 typename TPlanarMesh::TRay2D R2(TPlanarMesh::dest(e), TPlanarMesh::org(e->lPrev()));
00701 typename TPlanarMesh::TPoint2D p2 = R2.point( R2.t( point_ ) );
00702 typename TPlanarMesh::TRay2D R3(TPlanarMesh::org(e->lPrev()), TPlanarMesh::org(e));
00703 typename TPlanarMesh::TPoint2D p3 = R3.point( R3.t( point_ ) );
00704
00705 typename TPlanarMesh::TPoint2D::TValue d1 = squaredDistance(point_,p1);
00706 typename TPlanarMesh::TPoint2D::TValue d2 = squaredDistance(point_,p2);
00707 typename TPlanarMesh::TPoint2D::TValue d3 = squaredDistance(point_,p3);
00708
00709 if ((d1<d2) && (d1<d3))
00710 {
00711 edge = e;
00712 return false;
00713 }
00714 if ((d2<d3) && (d2<=d1))
00715 {
00716 edge = e->lNext();
00717 return false;
00718 }
00719 edge = e->lPrev();
00720 return false;
00721
00722
00723
00724
00725
00726
00727
00728
00729
00730
00731
00732
00733
00734
00735
00736
00737
00738
00739
00740
00741
00742
00743 }
00744 };
00745
00746 TEMPLATE_DEF
00747 class BrutePointLocatorVerbose
00748 {
00749 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00750 typename TPlanarMesh::TPoint2D point_;
00751 public:
00752 typename TPlanarMesh::TEdge* edge;
00753 std::ofstream stream;
00754 BrutePointLocatorVerbose( const typename TPlanarMesh::TPoint2D& iPoint ) : point_(iPoint), edge(NULL) {}
00755 bool findEdge( typename TPlanarMesh::TEdge* e )
00756 {
00757 typename TPlanarMesh::TEdge* ce = e;
00758 #if DEBUG_MESH
00759 stream << "---\n";
00760 stream << std::setprecision(20);
00761 #endif
00762 for (int i=0;i<3;++i)
00763 {
00764 #if DEBUG_MESH
00765 stream << TPlanarMesh::org(ce) << "-->" << TPlanarMesh::dest(ce) << ":" << prim::doubleTriangleArea(point_,TPlanarMesh::dest(ce),TPlanarMesh::org(ce)) << "\n";
00766 #endif
00767 #pragma LASS_TODO("Get rid of the epsilon!")
00768 if (prim::doubleTriangleArea(point_,TPlanarMesh::dest(ce),TPlanarMesh::org(ce))>1e-12)
00769 return true;
00770
00771
00772
00773 ce = ce->lNext();
00774 }
00775
00776 ce = e;
00777 T d1 = squaredDistance(TPlanarMesh::org(e),point_);
00778 T d2 = squaredDistance(TPlanarMesh::dest(e),point_);
00779 T d3 = squaredDistance(TPlanarMesh::dest(e->lNext()),point_);
00780
00781 if (d1<d2)
00782 {
00783 if (d1<d3)
00784 edge=e;
00785 else
00786 edge=e->lNext()->sym();
00787 }
00788 else
00789 {
00790 if (d2<d3)
00791 edge=e->sym();
00792 else
00793 edge=e->lNext()->sym();
00794 }
00795 return false;
00796 }
00797 };
00798
00799 }
00800
00801 TEMPLATE_DEF
00802 lass::io::MatlabOStream& operator<<( lass::io::MatlabOStream& ioOStream, const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge& iEdge )
00803 {
00804 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00805 ioOStream << typename TPlanarMesh::TLineSegment2D(
00806 TPlanarMesh::org(iEdge), TPlanarMesh::dest(iEdge) )
00807 << std::endl;
00808 return ioOStream;
00809 }
00810
00811 TEMPLATE_DEF
00812 lass::io::MatlabOStream& operator<<( lass::io::MatlabOStream& ioOStream, PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>& iMesh )
00813 {
00814 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
00815 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00816 typedef typename TPlanarMesh::TEdgeCallback TEdgeCallback;
00817 impl::EdgeToMatlab<T,PointHandle,EdgeHandle,FaceHandle> matlabWriter(&iMesh, ioOStream);
00818 TEdgeMarker edgeMarker( &iMesh, false );
00819 iMesh.forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
00820 iMesh.forAllPrimaryEdges( TEdgeCallback( &matlabWriter,
00821 &impl::EdgeToMatlab<T,PointHandle,EdgeHandle,FaceHandle>::edgeToMatlab ) );
00822 iMesh.forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
00823 iMesh.forAllPrimaryEdges( TEdgeCallback( &matlabWriter,
00824 &impl::EdgeToMatlab<T,PointHandle,EdgeHandle,FaceHandle>::vertexToMatlab ) );
00825 return ioOStream;
00826 }
00827
00828 TEMPLATE_DEF
00829 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::makeMaximalConvexPolygon(T iMaxSurface)
00830 {
00831 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00832 typedef impl::EdgeGatherer<T, PointHandle, EdgeHandle, FaceHandle> TEdgeGatherer;
00833 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
00834
00835 TEdgeMarker edgeMarker( this, false );
00836 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
00837 while (true)
00838 {
00839 TEdgeGatherer edgeGatherer( this );
00840 edgeGatherer.maxSurface = iMaxSurface;
00841 edgeGatherer.edgeList.clear();
00842 forAllPrimaryUndirectedEdgesCached( TEdgeCallback( &edgeGatherer, &TEdgeGatherer::makeConvexPolygon) );
00843 if (edgeGatherer.edgeList.size()>0)
00844 gcDeleteEdge( edgeGatherer.edgeList.front() );
00845 else
00846 break;
00847 }
00848 #if DEBUG_MESH
00849 std::cout << "PlanarMesh GC collected " << gc() << " edges" << std::endl;
00850 #endif
00851 }
00852
00853 TEMPLATE_DEF
00854 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::makeRectangular(T minAngle, T maxAngle)
00855 {
00856 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
00857 typedef impl::EdgeGatherer<T, PointHandle, EdgeHandle, FaceHandle> TEdgeGatherer;
00858 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
00859
00860 TEdgeMarker edgeMarker( this, false );
00861 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
00862 while (true)
00863 {
00864 TEdgeGatherer edgeGatherer( this );
00865 edgeGatherer.edgeList.clear();
00866 edgeGatherer.angleConstraintMin = minAngle;
00867 edgeGatherer.angleConstraintMax = maxAngle;
00868 forAllPrimaryUndirectedEdgesCached( TEdgeCallback( &edgeGatherer, &TEdgeGatherer::makeRectangular) );
00869 if (edgeGatherer.edgeList.size()==0)
00870 break;
00871 if (edgeGatherer.edgeList.size()>0)
00872 {
00873 gcDeleteEdge( edgeGatherer.edgeList.back() );
00874 edgeGatherer.edgeList.pop_back();
00875 }
00876 }
00877 #if DEBUG_MESH
00878 std::cout << "PlanarMesh GC collected " << gc() << " edges" << std::endl;
00879 #endif
00880 }
00881
00882
00883 TEMPLATE_DEF
00884 PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::PlanarMesh( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c)
00885 {
00886 allocateInTemp_ = false;
00887 tolerance_ = 1.0e-8;
00888 pointDistanceTolerance_ = 1.0e-8;
00889 TEdge* ea = makeEdge(a, b, true);
00890 TEdge* eb = makeEdge(b, c, true);
00891 TEdge* ec = makeEdge(c, a, true);
00892
00893
00894 TQuadEdge::splice(ea->sym(), eb);
00895 TQuadEdge::splice(eb->sym(), ec);
00896 TQuadEdge::splice(ec->sym(), ea);
00897
00898 startEdge_ = ec;
00899 lastLocateEdge_.reset(startEdge_);
00900 lastFloodEdge_.reset(startEdge_);
00901 edgeCount_ = 6;
00902 stackDepth_ = 0;
00903
00904 boundingPoints_.push_back(a);
00905 boundingPoints_.push_back(b);
00906 boundingPoints_.push_back(c);
00907 }
00908
00909 TEMPLATE_DEF
00910 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::init4( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c, const TPoint2D& d)
00911 {
00912 allocateInTemp_ = false;
00913 tolerance_ = T(1.0e-8);
00914 pointDistanceTolerance_ = T(1.0e-8);
00915
00916 TEdge* ea = makeEdge(a, b, true);
00917 TEdge* eb = makeEdge(b, c, true);
00918 TEdge* ec = makeEdge(c, d, true);
00919 TEdge* ed = makeEdge(d, a, true);
00920
00921 TQuadEdge::splice(ea->sym(), eb);
00922 TQuadEdge::splice(eb->sym(), ec);
00923 TQuadEdge::splice(ec->sym(), ed);
00924 TQuadEdge::splice(ed->sym(), ea);
00925
00926 if (prim::inCircle( c,d,a,b ))
00927 connect( ec, eb );
00928 else
00929 connect( eb, ea );
00930
00931 startEdge_ = ed;
00932 lastLocateEdge_.reset(startEdge_);
00933 lastFloodEdge_.reset(startEdge_);
00934
00935 edgeCount_ = 10;
00936 stackDepth_ = 0;
00937
00938 boundingPoints_.push_back(a);
00939 boundingPoints_.push_back(b);
00940 boundingPoints_.push_back(c);
00941 boundingPoints_.push_back(d);
00942 }
00943
00944 TEMPLATE_DEF
00945 PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::PlanarMesh( const prim::Aabb2D<T>& iAabb )
00946 {
00947 allocateInTemp_ = false;
00948 TPoint2D topleft(iAabb.min().x, iAabb.max().y);
00949 TPoint2D topright(iAabb.max().x, iAabb.max().y);
00950 TPoint2D bottomleft(iAabb.min().x, iAabb.min().y);
00951 TPoint2D bottomright(iAabb.max().x, iAabb.min().y);
00952 init4(topleft, bottomleft, bottomright, topright);
00953 }
00954
00955 TEMPLATE_DEF
00956 PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::PlanarMesh( const TPoint2D& a, const TPoint2D& b, const TPoint2D& c, const TPoint2D& d)
00957 {
00958 allocateInTemp_ = false;
00959 init4(a, b, c, d);
00960 }
00961
00962
00963 TEMPLATE_DEF
00964 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::deletePoint( typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* iEdge)
00965 {
00966 if (iEdge->handle().point_)
00967 free(iEdge->handle().point_);
00968 TEdge* currentEdge = iEdge;
00969 do
00970 {
00971 currentEdge->handle().point_ = NULL;
00972 currentEdge = currentEdge->oNext();
00973 } while ( currentEdge != iEdge );
00974 return true;
00975 }
00976
00977 TEMPLATE_DEF
00978 PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::~PlanarMesh( )
00979 {
00980 forAllVertices( TEdgeCallback(this, &PlanarMesh::deletePoint) );
00981 typename TQuadEdgeList::iterator qIt;
00982 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
00983 {
00984 (*qIt)->edgeDeconstrain();
00985 (*qIt)->faceDeconstrain();
00986 free(*qIt);
00987 }
00988 }
00989
00990 TEMPLATE_DEF
00991 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setTempQuadEdges( bool iAllocateInTemp )
00992 {
00993 allocateInTemp_ = iAllocateInTemp;
00994 if (!allocateInTemp_ )
00995 {
00996 std::copy(tempQuadEdgeList_.begin(),tempQuadEdgeList_.end(),std::back_inserter(quadEdgeList_));
00997 tempQuadEdgeList_.clear();
00998 }
00999 }
01000
01001
01002 TEMPLATE_DEF
01003 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::makeEmptyEdge( bool makeConstrained )
01004 {
01005 TQuadEdge* qe = make(TQuadEdge(makeConstrained));
01006 if (allocateInTemp_)
01007 tempQuadEdgeList_.push_back( qe );
01008 else
01009 quadEdgeList_.push_back( qe );
01010 edgeCount_ += 2;
01011
01012 TEdge* e = qe->edges();
01013
01014
01015
01016
01017
01018
01019
01020
01021 return e;
01022 }
01023
01024 TEMPLATE_DEF
01025 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::connect( TEdge* a, TEdge* b)
01026 {
01027 FaceHandle fa = faceHandle(a);
01028 FaceHandle fb = faceHandle(b);
01029 if ( fa != fb )
01030 {
01031 LASS_THROW("connect of edges would violate face constraint");
01032 }
01033 PointHandle hADest = pointHandle( a->sym() );
01034 PointHandle hB = pointHandle( b );
01035 TEdge* e = makeEdge( dest(a), org(b), false);
01036 TQuadEdge::splice( e, a->lNext() );
01037 TQuadEdge::splice( e->sym(), b );
01038
01039 setFaceHandle( e, fa );
01040 setPointHandle( a->sym(), hADest );
01041 setPointHandle( b, hB );
01042 return e;
01043 }
01044
01045 TEMPLATE_DEF
01046 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::split( TEdge* iEdge, T iWhere)
01047 {
01048 LASS_ENFORCE(iWhere>T(0) && iWhere<T(1));
01049 splitEdge(iEdge,along(iEdge,iWhere));
01050 return iEdge->lNext();
01051
01052
01053
01054
01055
01056
01057
01058
01059
01060
01061
01062
01063
01064
01065 }
01066
01067 TEMPLATE_DEF
01068 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::removeVertex( TEdge* iEdge)
01069 {
01070
01071 int n = vertexOrder(iEdge);
01072 TEdge* currentEdge = iEdge;
01073 for (int i=0;i<n;++i)
01074 {
01075 gcDeleteEdge(currentEdge);
01076 currentEdge = currentEdge->oNext();
01077 }
01078 gc();
01079 return true;
01080 }
01081
01082 TEMPLATE_DEF
01083 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fixEdge(TEdge *e)
01084
01085
01086
01087
01088 {
01089 if (e->isConstrained())
01090 return;
01091 TEdge *f = e->oPrev();
01092 TEdge *g = e->dNext();
01093
01094 if ( prim::inCircle( dest(e),dest(e->oNext()),org(e),dest(f)) )
01095 {
01096 swap(e);
01097 fixEdge(f);
01098 fixEdge(g);
01099 }
01100 }
01101
01102
01103 TEMPLATE_DEF
01104 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::safeSplitEdge(TEdge *e, const TPoint2D& iPoint )
01105
01106
01107
01108
01109
01110
01111 {
01112 TRay2D testRay1(org(e),dest(e));
01113 if (testRay1.t(dest(e))<=testRay1.t(iPoint))
01114 {
01115 LASS_THROW("Inconsistent splitting of constrained edge");
01116 }
01117 TRay2D testRay2(dest(e),org(e));
01118 if (testRay2.t(org(e))<=testRay2.t(iPoint))
01119 {
01120 LASS_THROW("Inconsistent splitting of constrained edge");
01121 }
01122 splitEdge(e,iPoint);
01123 }
01124
01125
01126 TEMPLATE_DEF
01127 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::splitEdge(TEdge *e, const TPoint2D& iPoint )
01128
01129
01130
01131
01132
01133
01134
01135
01136
01137
01138 {
01139 const TVector2D dir = direction(e);
01140 PointHandle iE = pointHandle(e);
01141 PointHandle iES= pointHandle(e->sym());
01142 EdgeHandle iLE = edgeHandle(e);
01143 EdgeHandle iRE = edgeHandle(e->sym());
01144
01145 TPoint2D thePoint = iPoint;
01146 TEdge* t = e->lNext();
01147 TQuadEdge::splice( e->sym(), t );
01148 setDest( thePoint, e );
01149 setPointHandle(e, iE);
01150 TEdge* ne = connect( e, t );
01151 if (e->isConstrained())
01152 {
01153
01154
01155 setOrientedEdgeHandle( e, iLE, iRE, dir );
01156 setOrientedEdgeHandle( ne, iLE, iRE, dir );
01157 ne->quadEdge()->edgeConstrain();
01158 }
01159
01160
01161 LASS_ASSERT( pointHandle(e) == iE );
01162 LASS_ASSERT( pointHandle(e->lNext()->sym()) == iES );
01163 }
01164
01165 TEMPLATE_DEF
01166 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::snap(const TPoint2D& x, const TPoint2D& a, const TPoint2D& b)
01167 {
01168
01169
01170
01171
01172
01173
01174
01175 if (x==a)
01176 return a;
01177 if (x==b)
01178 return b;
01179 T t1 = dot(x-a,b-a);
01180 T t2 = dot(x-b,a-b);
01181
01182 T t = std::max(t1,t2) / (t1 + t2);
01183
01184 if (prim::doubleTriangleArea(x,a,b)==T(0))
01185 return x;
01186
01187 if (t1>t2)
01188 {
01189 T rx1 = (T(1)-t)*a.x + t*b.x;
01190 T ry1 = (T(1)-t)*a.y + t*b.y;
01191 return TPoint2D(rx1,ry1);
01192 }
01193
01194 T rx2 = (T(1)-t)*b.x + t*a.x;
01195 T ry2 = (T(1)-t)*b.y + t*a.y;
01196
01197 return TPoint2D(rx2,ry2);
01198 }
01199
01200 TEMPLATE_DEF
01201 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::swap( TEdge* iEdge )
01202 {
01203 if ( iEdge->isConstrained() )
01204 {
01205 LASS_THROW( "cannot swap constrained edge" );
01206 }
01207 TEdge* e = iEdge;
01208 TEdge* a = e->oPrev();
01209 TEdge* b = e->sym()->oPrev();
01210
01211
01212
01213
01214
01215
01216
01217
01218
01219 PointHandle hA = pointHandle(e->oNext()->sym());
01220 PointHandle hB = pointHandle(e);
01221 PointHandle hC = pointHandle(e->sym());
01222 PointHandle hD = pointHandle(e->oPrev()->sym());
01223
01224 TQuadEdge::splice( e, a );
01225 TQuadEdge::splice( e->sym(), b );
01226 TQuadEdge::splice( e, a->lNext() );
01227 TQuadEdge::splice( e->sym(), b->lNext() );
01228 setOrg( dest(a), e );
01229 setDest( dest(b), e );
01230
01231 setPointHandle( e, hD );
01232 setPointHandle( e->sym(), hA );
01233
01234 LASS_ASSERT( leftOf( dest(e->lNext()), e ) );
01235 LASS_ASSERT( leftOf( dest(e->lNext()->lNext()), e->lNext() ) );
01236 LASS_ASSERT( leftOf( dest(e->lNext()->lNext()->lNext()), e->lNext()->lNext() ) );
01237 LASS_ASSERT( leftOf( dest(e->sym()->lNext()), e->sym() ) );
01238 LASS_ASSERT( leftOf( dest(e->sym()->lNext()->lNext()), e->sym()->lNext() ) );
01239 LASS_ASSERT( leftOf( dest(e->sym()->lNext()->lNext()->lNext()), e->sym()->lNext()->lNext() ) );
01240
01241 LASS_ASSERT( pointHandle( e->oNext()->sym() ) == hB );
01242 LASS_ASSERT( pointHandle( e->oPrev()->sym() ) == hC );
01243 }
01244
01245 TEMPLATE_DEF
01246 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::deleteEdge( TEdge* e )
01247 {
01248 if ( e->isConstrained() )
01249 {
01250 return false;
01251 }
01252
01253 while (startEdge_->quadEdge()==e->quadEdge())
01254 startEdge_=e->lNext();
01255
01256
01257 if ( *lastLocateEdge_==e
01258 || *lastLocateEdge_==e->rot()
01259 || *lastLocateEdge_==e->sym()
01260 || *lastLocateEdge_==e->sym()->rot())
01261 lastLocateEdge_.reset(startEdge_);
01262 if ( *lastFloodEdge_==e
01263 || *lastFloodEdge_==e->rot()
01264 || *lastFloodEdge_==e->sym()
01265 || *lastFloodEdge_==e->sym()->rot())
01266 lastFloodEdge_.reset(startEdge_);
01267
01268 TQuadEdge::splice( e, e->oPrev() );
01269 TQuadEdge::splice( e->sym(), e->sym()->oPrev() );
01270
01271 typename TQuadEdgeList::iterator it = std::find(quadEdgeList_.begin(),quadEdgeList_.end(),e->quadEdge());
01272 std::swap(*it, quadEdgeList_.back());
01273
01274 TQuadEdge* qe = quadEdgeList_.back();
01275 qe->edgeDeconstrain();
01276 qe->faceDeconstrain();
01277 quadEdgeList_.pop_back();
01278 free(qe);
01279
01280 edgeCount_ -= 2;
01281 return true;
01282 }
01283
01284 TEMPLATE_DEF
01285 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::gcDeleteEdge( TEdge* e )
01286 {
01287 if ( e->isConstrained() )
01288 {
01289 return false;
01290 }
01291
01292 while (startEdge_->quadEdge()==e->quadEdge())
01293 startEdge_=e->lNext();
01294
01295 if ( *lastLocateEdge_==e
01296 || *lastLocateEdge_==e->rot()
01297 || *lastLocateEdge_==e->sym()
01298 || *lastLocateEdge_==e->sym()->rot())
01299 lastLocateEdge_.reset(startEdge_);
01300 if ( *lastFloodEdge_==e
01301 || *lastFloodEdge_==e->rot()
01302 || *lastFloodEdge_==e->sym()
01303 || *lastFloodEdge_==e->sym()->rot())
01304 lastFloodEdge_.reset(startEdge_);
01305
01306 TQuadEdge::splice( e, e->oPrev() );
01307 TQuadEdge::splice( e->sym(), e->sym()->oPrev() );
01308
01309 TQuadEdge* qe = e->quadEdge();
01310 qe->edgeDeconstrain();
01311 qe->faceDeconstrain();
01312 qe->detach();
01313 qe->deleted = true;
01314
01315 edgeCount_ -= 2;
01316 return true;
01317 }
01318 TEMPLATE_DEF
01319 int PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::gc( )
01320 {
01321
01322
01323
01324
01325
01326 int lastMarker = quadEdgeList_.size()-1;
01327 int startMarker = 0;
01328 int collected = 0;
01329 int n = quadEdgeList_.size()-1;
01330
01331 while (startMarker<lastMarker)
01332 {
01333
01334 while (!quadEdgeList_[startMarker]->deleted && startMarker<n)
01335 ++startMarker;
01336
01337 while (quadEdgeList_[lastMarker]->deleted && lastMarker>0)
01338 --lastMarker;
01339
01340 if (quadEdgeList_[startMarker]->deleted && !quadEdgeList_[lastMarker]->deleted )
01341 std::swap(quadEdgeList_[startMarker],quadEdgeList_[lastMarker]);
01342 }
01343
01344
01345
01346 lastMarker = n;
01347 while (quadEdgeList_[lastMarker]->deleted && lastMarker>0)
01348 {
01349 --lastMarker;
01350 quadEdgeList_.pop_back();
01351 ++collected;
01352 }
01353 return collected;
01354 }
01355
01356
01357 TEMPLATE_DEF
01358 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::bruteForceLocate( const TPoint2D& iPoint ) const
01359 {
01360 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
01361 impl::BrutePointLocator<T, PointHandle, EdgeHandle, FaceHandle> bruteLocator( iPoint );
01362 const_cast<TPlanarMesh*>(this)->forAllFaces( TEdgeCallback( &bruteLocator, &impl::BrutePointLocator<T, PointHandle, EdgeHandle, FaceHandle>::findEdge ) );
01363 if (bruteLocator.edge==NULL)
01364 {
01365 impl::BrutePointLocator<T, PointHandle, EdgeHandle, FaceHandle> bruteLocator( iPoint );
01366 const_cast<TPlanarMesh*>(this)->forAllPrimaryEdges( TEdgeCallback( &bruteLocator, &impl::BrutePointLocator<T, PointHandle, EdgeHandle, FaceHandle>::findEdge ) );
01367 #if DEBUG_MESH
01368 if (bruteLocator.edge==NULL)
01369 {
01370 impl::BrutePointLocatorVerbose<T, PointHandle, EdgeHandle, FaceHandle> bruteLocatorVerbose( iPoint );
01371 bruteLocatorVerbose.stream.open("bruteforcelocation.txt");
01372 const_cast<TPlanarMesh*>(this)->forAllPrimaryEdges( TEdgeCallback( &bruteLocatorVerbose, &impl::BrutePointLocatorVerbose<T, PointHandle, EdgeHandle, FaceHandle>::findEdge ) );
01373 bruteLocatorVerbose.stream.close();
01374 return bruteLocatorVerbose.edge;
01375 }
01376 #endif
01377 return bruteLocator.edge;
01378 }
01379 return bruteLocator.edge;
01380 }
01381
01382
01383 TEMPLATE_DEF
01384 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::bruteForceExactLocate( const TPoint2D& iPoint ) const
01385 {
01386 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
01387 impl::BrutePointExactLocator<T, PointHandle, EdgeHandle, FaceHandle> brutePointLocator( iPoint );
01388 const_cast<TPlanarMesh*>(this)->forAllVertices( TEdgeCallback( &brutePointLocator, &impl::BrutePointExactLocator<T, PointHandle, EdgeHandle, FaceHandle>::findPoint ) );
01389 return brutePointLocator.edge;
01390 }
01391
01392 TEMPLATE_DEF
01393 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::isBoundingPoint( const TPoint2D& iPoint ) const
01394 {
01395 size_t length = boundingPoints_.size();
01396 for (size_t i=0;i<length;++i)
01397 {
01398 if (boundingPoints_[i]==iPoint)
01399 return true;
01400 }
01401 return false;
01402 }
01403
01404
01405
01406 TEMPLATE_DEF
01407 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::locate( const TPoint2D& iPoint, TEdge* iHint ) const
01408 {
01409 if (iHint)
01410 *lastLocateEdge_ = iHint;
01411 TEdge*& lastLocateEdge = *lastLocateEdge_;
01412 long edgesPassed = 0;
01413
01414 TEdge* e = lastLocateEdge;
01415 while (edgesPassed<(edgeCount_+2))
01416 {
01417 continueSearch:
01418 ++edgesPassed;
01419 const TPoint2D& eorg = fastOrg(e);
01420 const TPoint2D& edest = fastDest(e);
01421
01422 if ( eorg == iPoint )
01423 {
01424 lastLocateEdge = e;
01425 return e;
01426 }
01427 if ( edest == iPoint )
01428 {
01429 e = e->sym();
01430 lastLocateEdge = e;
01431 return e;
01432 }
01433 if ( fastRightOf( iPoint, e ) )
01434 e = e->sym();
01435
01436
01437 bool hasALeftFace = true;
01438 if (isBoundingPoint(eorg))
01439 hasALeftFace = fastHasLeftFace(e);
01440
01441 if (hasALeftFace)
01442 {
01443
01444
01445
01446
01447
01448
01449 if ( fastLeftOf( iPoint, e->oNext()) )
01450 {
01451 e = e->oNext();
01452 continue;
01453 }
01454 TEdge* ce = e;
01455 #pragma LASS_TODO("Optimize")
01456
01457
01458 size_t loopOrder = chainOrder(e)-2;
01459 for (size_t i=0;i<loopOrder;++i)
01460 {
01461 if ( fastLeftOf( iPoint, ce->dPrev()) )
01462 {
01463 e = ce->dPrev();
01464 goto continueSearch;
01465 }
01466 ce = ce->lNext();
01467 }
01468
01469 TRay2D R1(fastOrg(e), fastDest(e));
01470 TPoint2D p1 = R1.point( R1.t( iPoint ) );
01471 TRay2D R2(fastDest(e), fastOrg(e->lPrev()));
01472 TPoint2D p2 = R2.point( R2.t( iPoint ) );
01473 TRay2D R3(fastOrg(e->lPrev()), fastOrg(e));
01474 TPoint2D p3 = R3.point( R3.t( iPoint ) );
01475
01476 typename TPoint2D::TValue d1 = squaredDistance(iPoint,p1);
01477 typename TPoint2D::TValue d2 = squaredDistance(iPoint,p2);
01478 typename TPoint2D::TValue d3 = squaredDistance(iPoint,p3);
01479
01480
01481
01482
01483
01484
01485
01486 if ((d1<d2) && (d1<d3))
01487 {
01488 lastLocateEdge = e;
01489 return e;
01490 }
01491 if ((d2<d3) && (d2<=d1))
01492 {
01493 e = e->lNext();
01494 lastLocateEdge = e;
01495 return e;
01496 }
01497 e = e->lPrev();
01498 lastLocateEdge = e;
01499 return e;
01500 }
01501
01502 if (onEdge(iPoint,e))
01503 {
01504 e = e->sym();
01505 lastLocateEdge = e;
01506 return e;
01507 }
01508
01509 if (rightOf(iPoint, e->oPrev()))
01510 {
01511 e = e->oPrev()->sym();
01512 continue;
01513 }
01514 if (rightOf(iPoint,e->dNext()))
01515 {
01516 e = e->dNext()->sym();
01517 continue;
01518 }
01519 }
01520
01521
01522 e = bruteForceLocate(iPoint);
01523 lastLocateEdge = e;
01524 return e;
01525 }
01526
01527 TEMPLATE_DEF
01528 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::pointLocate( const TPoint2D& iPoint ) const
01529 {
01530 TEdge*& lastLocateEdge = *lastLocateEdge_;
01531 long edgesPassed = 0;
01532
01533 TEdge* e = lastLocateEdge;
01534 while (edgesPassed<(edgeCount_+2))
01535 {
01536 ++edgesPassed;
01537 if ( org( e ) == iPoint )
01538 {
01539 lastLocateEdge = e;
01540 return e;
01541 }
01542 if ( dest( e ) == iPoint )
01543 {
01544 e = e->sym();
01545 lastLocateEdge = e;
01546 return e;
01547 }
01548 if ( rightOf( iPoint, e ) )
01549 e = e->sym();
01550
01551 if (hasLeftFace(e))
01552 {
01553 if ( iPoint == org(e->lPrev()) )
01554 {
01555 e = e->lPrev();
01556 lastLocateEdge = e;
01557 return e;
01558 }
01559 if ( leftOf( iPoint, e->oNext()) )
01560 {
01561 e = e->oNext();
01562 continue;
01563 }
01564 if ( leftOf( iPoint, e->dPrev()) )
01565 {
01566 e = e->dPrev();
01567 continue;
01568 }
01569 }
01570
01571 if (rightOf(iPoint, e->oPrev()))
01572 {
01573 e = e->oPrev()->sym();
01574 continue;
01575 }
01576 if (rightOf(iPoint,e->dNext()))
01577 {
01578 e = e->dNext()->sym();
01579 continue;
01580 }
01581 }
01582
01583 e = bruteForceExactLocate(iPoint);
01584 LASS_ASSERT(e!=NULL);
01585 lastLocateEdge = e;
01586 return e;
01587 LASS_THROW( "pointLocate: could not find point");
01588 }
01589
01590
01591
01592 TEMPLATE_DEF
01593 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::shoot( const TRay2D& iRay ) const
01594 {
01595 TEdge* locateEdge = locate(iRay.support());
01596 TEdge* startEdge = locateEdge;
01597 if (!startEdge)
01598 return NULL;
01599
01600 if (org(startEdge)==iRay.support())
01601 {
01602 TEdge* e(startEdge);
01603
01604 int vOrder = vertexOrder(e);
01605 for (int i=0;i<vOrder+1;++i)
01606 {
01607
01608
01609
01610
01611
01612
01613 if ( num::abs(prim::doubleTriangleArea(iRay.support(),iRay.point(T(1)),dest(e)))<tolerance_
01614 && iRay.t(dest(e)) > T(0) )
01615 return e;
01616 e = e->oNext();
01617 }
01618 e = e;
01619 }
01620
01621 do
01622 {
01623 TEdge* e(startEdge);
01624 lass::prim::Side lastSide = iRay.classify(org(e));
01625 do
01626 {
01627 lass::prim::Side currentSide = iRay.classify(dest(e));
01628 if (currentSide==lass::prim::sSurface)
01629 return e->sym();
01630 if (lastSide==lass::prim::sRight && lastSide!=currentSide)
01631 return e;
01632 lastSide = currentSide;
01633 e = e->lNext();
01634 }
01635 while (e!=startEdge);
01636 startEdge = startEdge->oNext();
01637 } while (startEdge!=locateEdge);
01638
01639 #if DEBUG_MESH
01640
01641 {
01642 lass::io::MatlabOStream bugMesh;
01643 bugMesh.open( "shoot_ray.m" );
01644 bugMesh << std::setprecision(15);
01645 bugMesh << *const_cast<PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>*>(this);
01646 bugMesh.close();
01647 bugMesh.open( "shoot_ray_edges.m" );
01648 bugMesh.setColor(lass::io::mcBlue);
01649 bugMesh << TLineSegment2D(iRay.support(),iRay.point(1.0));
01650 do
01651 {
01652 TEdge* e(startEdge);
01653 lass::prim::Side lastSide = iRay.classify(org(e));
01654 bugMesh.setColor(lass::io::mcRed);
01655 bugMesh << TLineSegment2D(org(startEdge),dest(startEdge));
01656 do
01657 {
01658 bugMesh.setColor(lass::io::mcGreen);
01659 bugMesh << TLineSegment2D(org(e),dest(e));
01660 lass::prim::Side currentSide = iRay.classify(dest(e));
01661 if (lastSide==lass::prim::sRight && lastSide!=currentSide)
01662 return e;
01663 lastSide = currentSide;
01664 e = e->lNext();
01665 }
01666 while (e!=startEdge);
01667 startEdge = startEdge->oNext();
01668 } while (startEdge!=locateEdge);
01669 bugMesh.close();
01670 }
01671 #endif
01672
01673 return NULL;
01674 }
01675
01676
01677 TEMPLATE_DEF
01678 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::pointShoot( const TRay2D& iRay ) const
01679 {
01680 TEdge* locateEdge = pointLocate(iRay.support());
01681 LASS_ASSERT(isBoundingPoint(org(locateEdge)) || allEqualChainOrder(locateEdge));
01682 TEdge* startEdge = locateEdge;
01683 if (!startEdge)
01684 return NULL;
01685
01686 TEdge* e(startEdge);
01687
01688 int vOrder = vertexOrder(e);
01689 for (int i=0;i<vOrder+1;++i)
01690 {
01691
01692
01693
01694
01695
01696
01697 if ( num::abs(prim::doubleTriangleArea(iRay.support(),iRay.point(T(1)),dest(e)))<tolerance_
01698 && iRay.t(dest(e)) > T(0) )
01699 return e;
01700 e = e->oNext();
01701 }
01702 e = e;
01703
01704 do
01705 {
01706 TEdge* e(startEdge);
01707 lass::prim::Side lastSide = iRay.classify(org(e));
01708 do
01709 {
01710 lass::prim::Side currentSide = iRay.classify(dest(e));
01711 if (lastSide==lass::prim::sRight && lastSide!=currentSide)
01712 return e;
01713 lastSide = currentSide;
01714 e = e->lNext();
01715 }
01716 while (e!=startEdge);
01717 startEdge = startEdge->oNext();
01718 } while (startEdge!=locateEdge);
01719
01720 LASS_THROW("pointShoot, could not find suitable triangle");
01721 return NULL;
01722 }
01723
01724
01725
01726 TEMPLATE_DEF
01727 template <typename OutputIterator>
01728 OutputIterator PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::walkIntersections( const TLineSegment2D& iSegment, OutputIterator oIntersections) const
01729 {
01730 std::vector<TEdge*> crossedEdges;
01731 walk(iSegment,std::back_inserter(crossedEdges));
01732 const size_t n = crossedEdges.size();
01733 for (size_t i=0;i<n;++i)
01734 {
01735 TPoint2D intersection;
01736 if (impl::fastIntersect(iSegment.tail(),iSegment.head(),fastOrg(crossedEdges[i]),fastDest(crossedEdges[i]),intersection)!=lass::prim::rOne)
01737 {
01738
01739 (*oIntersections++) = std::pair<TPoint2D,TEdge*>(fastOrg(crossedEdges[i]),crossedEdges[i]);
01740 if (squaredDistance(fastOrg(crossedEdges[i]),fastDest(crossedEdges[i]))<squaredDistance(iSegment.tail(),iSegment.head()))
01741 (*oIntersections++) = std::pair<TPoint2D,TEdge*>(fastDest(crossedEdges[i]),crossedEdges[i]);
01742 else
01743 (*oIntersections++) = std::pair<TPoint2D,TEdge*>(iSegment.head(),crossedEdges[i]);
01744 }
01745 else
01746 {
01747 (*oIntersections++) = std::pair<TPoint2D,TEdge*>(intersection,crossedEdges[i]);
01748 }
01749 }
01750 return oIntersections;
01751 }
01752
01753
01754
01755 TEMPLATE_DEF
01756 template <typename OutputIterator>
01757 OutputIterator PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::walk( const TLineSegment2D& iSegment, OutputIterator crossedEdges ) const
01758 {
01759 TEdge* e=NULL;
01760 e = shoot(TRay2D(iSegment.tail(),iSegment.vector()));
01761
01762 if (!e)
01763 {
01764 LASS_THROW("Could not shoot initial ray in walk");
01765 }
01766 if (inConvexCell(iSegment.head(),e))
01767 return crossedEdges;
01768 if (dest(e)==iSegment.head())
01769 {
01770 (*crossedEdges++) = e;
01771 return crossedEdges;
01772 }
01773
01774 while ( !leftOf(iSegment.head(),e)
01775 || ( (num::abs(prim::doubleTriangleArea(dest(e),iSegment.head(),iSegment.tail()))<tolerance_ )
01776 && (num::abs(prim::doubleTriangleArea(org(e),iSegment.head(),iSegment.tail()))<tolerance_ ) ) )
01777 {
01778 (*crossedEdges++) = e;
01779
01780
01781
01782
01783
01784
01785
01786 TEdge* ce = e->sym()->lNext();
01787 #pragma LASS_TODO("Optimize")
01788
01789
01790 TEdge* oldE = e;
01791 for (int i=0;i<chainOrder(e);++i)
01792 {
01793 if ( weakCcw( iSegment.tail(), iSegment.head(), dest(ce) ) )
01794 {
01795 e = ce;
01796 break;
01797 }
01798 ce = ce->lNext();
01799 }
01800 if (e==oldE)
01801 {
01802 LASS_THROW("Planarmesh: stuck in walk");
01803 }
01804 }
01805 return crossedEdges;
01806 }
01807
01808
01809 TEMPLATE_DEF
01810 std::pair<int, typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge*> PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::walkTillConstrained( const TRay2D& iRay) const
01811 {
01812 int nCrossed = 0;
01813 TEdge* e=NULL;
01814 TLineSegment2D segment(iRay.support(),iRay.support()+iRay.direction());
01815 e = shoot(iRay);
01816
01817 if (!e)
01818 {
01819 LASS_THROW("Could not shoot initial ray in walk");
01820 }
01821 while ( !e->isConstrained())
01822 {
01823
01824
01825
01826
01827
01828
01829
01830 TEdge* ce = e->sym()->lNext();
01831 #pragma LASS_TODO("Optimize")
01832
01833
01834 TEdge* oldE = e;
01835 int n = chainOrder(e);
01836 for (int i=0;i<n;++i)
01837 {
01838 if ( weakCcw( segment.tail(), segment.head(), dest(ce) ) )
01839 {
01840 e = ce;
01841 ++nCrossed;
01842 break;
01843 }
01844 ce = ce->lNext();
01845 }
01846 if (e==oldE)
01847 {
01848 LASS_THROW("Planarmesh: stuck in walkTillConstrained");
01849 }
01850 }
01851 return std::make_pair(nCrossed,e);
01852 }
01853
01854
01855
01856
01857 TEMPLATE_DEF
01858 template <typename OutputIterator>
01859 OutputIterator PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::pointWalk( const TLineSegment2D& iSegment, OutputIterator crossedEdges ) const
01860 {
01861 TEdge* e=NULL;
01862 e = pointShoot(TRay2D(iSegment.tail(),iSegment.vector()));
01863 LASS_ASSERT(isBoundingPoint(org(e)) || allEqualChainOrder(e));
01864 if (!e)
01865 {
01866 LASS_THROW("Could not shoot initial ray in pointWalk");
01867 }
01868 if (dest(e)==iSegment.head())
01869 {
01870 (*crossedEdges++) = e;
01871 return crossedEdges;
01872 }
01873
01874 while ( !leftOf(iSegment.head(),e)
01875 || ( (num::abs(prim::doubleTriangleArea(dest(e),iSegment.head(),iSegment.tail()))<tolerance_ )
01876 && (num::abs(prim::doubleTriangleArea(org(e),iSegment.head(),iSegment.tail()))<tolerance_ ) ) )
01877 {
01878 (*crossedEdges++) = e;
01879
01880
01881
01882
01883
01884
01885
01886 TEdge* ce = e->sym()->lNext();
01887 #pragma LASS_TODO("Optimize")
01888
01889
01890 for (int i=0;i<chainOrder(e)-1;++i)
01891 {
01892 if ( weakCcw( iSegment.tail(), iSegment.head(), dest(ce) ) )
01893 {
01894 e = ce;
01895 break;
01896 }
01897 ce = ce->lNext();
01898 }
01899 }
01900 return crossedEdges;
01901 }
01902
01903
01904 TEMPLATE_DEF
01905 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::triangulate( TEdge* iEdge )
01906
01907
01908
01909
01910
01911
01912
01913
01914
01915
01916 {
01917 TEdge *first = iEdge;
01918 TEdge *a, *b, *e, *t1, *t2, *last = first->lPrev();
01919
01920 while (first->lNext()->lNext() != last)
01921 {
01922 e = first->lNext();
01923 t1 = first;
01924 while (e != last)
01925 {
01926 t2 = e->lNext();
01927 if (t2 == last && t1 == first)
01928 break;
01929 if (leftOf(dest(e),t1))
01930 {
01931 if (t1 == first)
01932 t1 = first = connect(e, t1)->sym();
01933 else
01934 t1 = connect(e, t1)->sym();
01935 a = t1->oPrev(), b = t1->dNext();
01936 fixEdge(a);
01937 fixEdge(b);
01938 e = t2;
01939 }
01940 else
01941 {
01942 t1 = e;
01943 e = t2;
01944 }
01945 }
01946 }
01947 a = last->lNext(), b = last->lPrev();
01948 fixEdge(a);
01949 fixEdge(b);
01950 fixEdge(last);
01951 }
01952
01953
01954
01955
01956
01957
01958
01959 TEMPLATE_DEF
01960 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::insertSite( const TPoint2D& iPoint, bool makeDelaunay, bool forceOnEdge )
01961 {
01962 TEdge* e = locate( iPoint );
01963 if (e==NULL)
01964 {
01965 locate( iPoint );
01966 LASS_ASSERT( e!=NULL);
01967 }
01968 T sqDistOrg = prim::squaredDistance(org(e),iPoint);
01969 T sqDistDest = prim::squaredDistance(dest(e),iPoint);
01970
01971 if (sqDistOrg<pointDistanceTolerance_*pointDistanceTolerance_)
01972 return e;
01973 if (sqDistDest<pointDistanceTolerance_*pointDistanceTolerance_)
01974 return e->sym();
01975
01976 bool hasLeft = hasLeftFace(e);
01977 bool hasRight = hasRightFace(e);
01978
01979 if (!hasLeft && !hasRight)
01980 {
01981 #if DEBUG_MESH
01982 lass::io::MatlabOStream bugMesh;
01983 bugMesh.open( "bugMesh.m" );
01984 bugMesh << *this;
01985 bugMesh.close();
01986 #endif
01987 throw std::runtime_error("insertSite: edge does not have any faces");
01988 }
01989
01990 bool isOnEdge = onEdge(iPoint, e) || forceOnEdge;
01991
01992 if (!isOnEdge && TLine2D(org(e),dest(e)).squaredDistance(iPoint)<T(1.05)*pointDistanceTolerance_*pointDistanceTolerance_)
01993 {
01994
01995
01996 isOnEdge = true;
01997 TPoint2D x = snap(iPoint, org(e), dest(e));
01998 return insertSite(x,makeDelaunay,true);
01999 }
02000
02001 bool insideLeft = hasLeft && (isOnEdge || leftOf(iPoint, e)) &&
02002 rightOf(iPoint, e->oNext()) && rightOf(iPoint, e->dPrev());
02003 bool insideRight = hasRight && (isOnEdge || rightOf(iPoint, e)) &&
02004 leftOf(iPoint, e->oPrev()) && leftOf(iPoint, e->dNext());
02005
02006
02007
02008 {
02009 TPoint2D p1 = org(e);
02010 TPoint2D p2 = dest(e);
02011 TPoint2D p3 = dest(e->lNext());
02012
02013 T s1 = prim::doubleTriangleArea(iPoint,p1,p2);
02014 T s2 = prim::doubleTriangleArea(iPoint,p2,p3);
02015 T s3 = prim::doubleTriangleArea(iPoint,p3,p1);
02016
02017 if (isOnEdge)
02018 {
02019 if ( s1*s2 < T(0) || s2*s3 < T(0) || s1*s3 < T(0) )
02020 {
02021 if (squaredDistance(org(e),iPoint)<squaredDistance(dest(e),iPoint))
02022 {
02023 if (squaredDistance(org(e),iPoint)<pointDistanceTolerance_*pointDistanceTolerance_)
02024 return insertSite(org(e),makeDelaunay,true);
02025 else
02026 {
02027
02028
02029 std::cout << "Numerical instability detected in lass::mesh\n";
02030 }
02031 }
02032 else
02033 {
02034 if (squaredDistance(dest(e),iPoint)<pointDistanceTolerance_*pointDistanceTolerance_)
02035 return insertSite(dest(e),makeDelaunay,true);
02036 else
02037 {
02038
02039
02040 std::cout << "Numerical instability detected in lass::mesh\n";
02041 }
02042 }
02043 }
02044 }
02045 else
02046 {
02047 LASS_ASSERT( s1*s2 > T(0) );
02048 LASS_ASSERT( s2*s3 > T(0) );
02049 LASS_ASSERT( s1*s3 > T(0) );
02050 }
02051 }
02052
02053
02054 if (insideLeft && iPoint == dest(e->oNext()))
02055 return e->lPrev();
02056 if (insideRight && iPoint == dest(e->oPrev()))
02057 return e->dNext();
02058
02059 if ( isOnEdge )
02060 {
02061 static int passCount2 = 0;
02062 ++passCount2;
02063
02064 TPoint2D x = snap(iPoint, org(e), dest(e));
02065 T sqDistOrg = prim::squaredDistance(org(e),x);
02066 T sqDistDest = prim::squaredDistance(dest(e),x);
02067
02068 if (sqDistOrg<pointDistanceTolerance_*pointDistanceTolerance_)
02069 return e;
02070 if (sqDistDest<pointDistanceTolerance_*pointDistanceTolerance_)
02071 return e->sym();
02072
02073
02074 if (hasRight && hasLeft)
02075 {
02076
02077 TEdge *a, *b, *c, *d;
02078 a = e->oPrev();
02079 b = e->dNext();
02080 c = e->lNext();
02081 d = e->lPrev();
02082 safeSplitEdge(e, x);
02083 connect(e, e->lPrev());
02084 connect(e->oPrev(), e->sym());
02085 fixEdge(a);
02086 fixEdge(b);
02087 fixEdge(c);
02088 fixEdge(d);
02089 }
02090 else
02091 {
02092
02093 if (hasRight)
02094 e = e->sym();
02095 TEdge *c = e->lNext();
02096 TEdge *d = e->lPrev();
02097 safeSplitEdge(e, x);
02098 connect(e, e->lPrev());
02099 fixEdge(c);
02100 fixEdge(d);
02101 }
02102 int vOrder = vertexOrder(e->sym());
02103 LASS_ASSERT(vOrder>2);
02104 LASS_ASSERT(x==dest(e));
02105 LASS_ASSERT(allEqualChainOrder(e->sym()));
02106 return e->sym();
02107 }
02108
02109
02110
02111
02112 PointHandle pH = pointHandle(e);
02113 TEdge* base = makeEdge(org(e),iPoint,false);
02114 TQuadEdge::splice(base,e);
02115 setPointHandle(e, pH);
02116 TEdge* startBase = base->sym();
02117
02118 do
02119 {
02120 base = connect( e, base->sym() );
02121 e = base->oPrev();
02122 } while (e->dPrev()!=startBase);
02123
02124 if ( makeDelaunay )
02125 {
02126
02127 while (true)
02128 {
02129 TEdge* t=e->oPrev();
02130 if ( !e->isConstrained() && prim::inCircle(org(e),dest(t),dest(e),iPoint))
02131 {
02132 swap(e);
02133 e=e->oPrev();
02134 }
02135 else
02136 {
02137 if (e->lPrev()==startBase)
02138 return base->sym();
02139 else
02140 e = e->oNext()->lPrev();
02141 }
02142 }
02143 }
02144 int vOrder = vertexOrder(base->sym());
02145 LASS_ASSERT(vOrder>2);
02146 LASS_ASSERT(iPoint==dest(base));
02147 LASS_ASSERT(allEqualChainOrder(base->sym()));
02148 return base->sym();
02149 }
02150
02151
02152
02153
02154
02155
02156 TEMPLATE_DEF
02157 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::insertEdge( const TLineSegment2D& iSegment, EdgeHandle iLeftHandle, EdgeHandle iRightHandle, PointHandle iPointHandle, bool iForcePointHandle, bool makeDelaunay )
02158 {
02159 #if DEBUG_MESH
02160 std::cout << "Inserting : " << iSegment << "\n";
02161 static int passCountMesh = 0;
02162 ++passCountMesh;
02163 char buf[128];
02164 sprintf(buf,"debug_mesh_%d.m",passCountMesh);
02165 lass::io::MatlabOStream debugMesh;
02166 debugMesh.open(buf);
02167 debugMesh << *this;
02168 debugMesh.close();
02169 #endif
02170 TEdge *ea, *eb;
02171 TPoint2D aa, bb, fbb, faa;
02172 if (ea = insertSite(iSegment.tail()),makeDelaunay)
02173 {
02174 aa = org(ea);
02175 if (iForcePointHandle)
02176 setPointHandle(ea, iPointHandle);
02177
02178 }
02179 if (eb = insertSite(iSegment.head()),makeDelaunay)
02180 {
02181 bb = org(eb);
02182 if (iForcePointHandle)
02183 setPointHandle(eb, iPointHandle);
02184 }
02185 fbb = bb;
02186 faa = aa;
02187
02188 if (ea == NULL || eb == NULL)
02189 {
02190 LASS_THROW("insertEdge: could not insert endpoints of edge");
02191 }
02192
02193 if (org(ea)!=aa)
02194 {
02195 ea=locate(aa);
02196 if (ea==NULL)
02197 {
02198 LASS_THROW("insertEdge: could not locate an endpoint");
02199 }
02200
02201 if (!(aa == org(ea)))
02202 ea = ea->sym();
02203 if (!(aa == org(ea)))
02204 {
02205 LASS_THROW("insertEdge: point a is not an endpoint of ea");
02206 }
02207 }
02208
02209 if (aa==bb)
02210 {
02211 return ea;
02212 }
02213
02214
02215 TEdge* ce = ea;
02216 int vOrder = vertexOrder(ea);
02217 for (int i=0;i<vOrder;++i)
02218 {
02219 if (dest(ce)==fbb)
02220 {
02221 ce->quadEdge()->edgeConstrain();
02222 setOrientedEdgeHandle( ce, iLeftHandle, iRightHandle, iSegment.vector() );
02223 return ce;
02224 }
02225 ce = ce->oNext();
02226 }
02227 if (distance(aa,bb)<pointDistanceTolerance_ )
02228 {
02229 LASS_THROW("insertEdge: both ends map to same vertex within requested numerical precision");
02230 }
02231 ce = ea;
02232 for (int i=0;i<vOrder;++i)
02233 {
02234
02235 if ( prim::dot(direction(ce), iSegment.vector()) > T(0)
02236 && num::abs(lass::prim::doubleTriangleArea(dest(ce),faa,fbb))<tolerance_)
02237 {
02238 ce->quadEdge()->edgeConstrain();
02239 setOrientedEdgeHandle( ce, iLeftHandle, iRightHandle, iSegment.vector() );
02240
02241 return insertEdge( TLineSegment2D( dest(ce), fbb), iLeftHandle, iRightHandle, iPointHandle, iForcePointHandle, makeDelaunay );
02242 }
02243
02244 ce = ce->oNext();
02245 }
02246
02247 TVector2D segmentDirection(fbb-faa);
02248 std::vector< TEdge* > insertedEdges;
02249 std::vector< TPoint2D > insertedPoints;
02250 std::vector< TPoint2D > finalInsertedPoints;
02251 std::vector< TEdge* > crossedEdges;
02252 std::vector< TEdge* > filteredEdges;
02253
02254 static int passCount=0;
02255 ++passCount;
02256
02257 LASS_ASSERT(allEqualChainOrder(ea));
02258 LASS_ASSERT(allEqualChainOrder(eb));
02259 pointWalk(TLineSegment2D(faa,fbb),std::back_inserter(crossedEdges));
02260 #if DEBUG_MESH
02261 std::cout << "Walk returned segments " << crossedEdges.size() << "\n";
02262 std::cout << std::setprecision(15);
02263 #endif
02264
02265
02266 insertedPoints.push_back(faa);
02267 for (size_t i=0;i<crossedEdges.size();++i)
02268 {
02269 bool computeIntersection = (crossedEdges[i]->isConstrained());
02270 TPoint2D eorg = org(crossedEdges[i]);
02271 TPoint2D edest= dest(crossedEdges[i]);
02272 bool noCommonPoints = eorg!=faa && eorg!=fbb && edest!=faa && edest!=fbb;
02273 if ( computeIntersection
02274 && noCommonPoints)
02275 {
02276 TLine2D other(eorg,edest);
02277 TPoint2D x;
02278
02279 if (prim::intersect(TLine2D(aa,bb),other,x)==prim::rOne)
02280 {
02281 TEdge* npe = insertSite(x,true,true);
02282 TPoint2D nx = org(npe);
02283
02284
02285
02286
02287
02288 if (nx!=insertedPoints.back())
02289 {
02290 insertedPoints.push_back(nx);
02291 #if DEBUG_MESH
02292 std::cout << "-> Intersection " << x << " filtered to " << nx << "\n";
02293 #endif
02294 break;
02295 }
02296 }
02297 }
02298 if (noCommonPoints)
02299 filteredEdges.push_back(crossedEdges[i]);
02300 }
02301 if (fbb!=insertedPoints.back())
02302 insertedPoints.push_back(fbb);
02303
02304
02305 if (insertedPoints.size()>2)
02306 {
02307 TEdge* ce = NULL;
02308 TEdge* bce = NULL;
02309 for (size_t i=0;i<insertedPoints.size()-1;++i)
02310 {
02311 ce = insertEdge( TLineSegment2D(insertedPoints[i],insertedPoints[i+1]), iLeftHandle, iRightHandle, iPointHandle, iForcePointHandle, makeDelaunay );
02312 if (i==0)
02313 bce = ce;
02314 }
02315 if ( org(bce) != faa )
02316 {
02317 bce = pointLocate( faa );
02318 }
02319 LASS_ASSERT( org(bce)==faa);
02320
02321 return bce;
02322 }
02323
02324 std::vector< TEdge* > toSwapEdges;
02325
02326
02327 bool madeConstraint = false;
02328
02329 for (size_t i=0;i<filteredEdges.size();++i)
02330 {
02331
02332 TPoint2D a = org(filteredEdges[i]);
02333 TPoint2D b = dest(filteredEdges[i]);
02334 TPoint2D c = dest(filteredEdges[i]->lNext());
02335 TPoint2D d = dest(filteredEdges[i]->sym()->lNext());
02336 bool swappedCcw1 = prim::ccw(d,b,c);
02337 bool swappedCcw2 = prim::ccw(a,d,c);
02338 if (!swappedCcw1 || !swappedCcw2)
02339 {
02340 #if DEBUG_MESH
02341 lass::io::MatlabOStream bugMesh;
02342 bugMesh.open( "swap_constrained.m" );
02343 bugMesh << *this;
02344 for (int j=0;j<filteredEdges.size();++j)
02345 {
02346 bugMesh.setColor( lass::io::mcBlue);
02347 bugMesh << TLineSegment2D(org(filteredEdges[j]),dest(filteredEdges[j]));
02348 }
02349 bugMesh.setColor( lass::io::mcRed );
02350 bugMesh << TLineSegment2D(a,b);
02351 bugMesh.setColor( lass::io::mcGreen );
02352 bugMesh << TLineSegment2D(faa,fbb);
02353 bugMesh.close();
02354 #endif
02355 toSwapEdges.push_back(filteredEdges[i]);
02356
02357
02358 }
02359 else
02360 {
02361 if (filteredEdges[i]->quadEdge()->isConstrained())
02362 {
02363 LASS_THROW("found constrained edge where I should not find one!");
02364 }
02365 swap(filteredEdges[i]);
02366 TPoint2D eorg = org(filteredEdges[i]);
02367 TPoint2D edest = dest(filteredEdges[i]);
02368 T onEdgeOrg = num::abs(prim::doubleTriangleArea(eorg,edest,faa));
02369 T onEdgeDest = num::abs(prim::doubleTriangleArea(eorg,edest,fbb));
02370
02371
02372 if (onEdgeOrg<tolerance_ && onEdgeDest<tolerance_)
02373 {
02374 filteredEdges[i]->quadEdge()->edgeConstrain();
02375 #if DEBUG_MESH
02376 std::cout << "@ Constraining " << org(filteredEdges[i]) << "-->" << dest(filteredEdges[i]) << "\n";
02377 #endif
02378 setOrientedEdgeHandle( filteredEdges[i], iLeftHandle, iRightHandle, iSegment.vector() );
02379 if (toSwapEdges.size()>0)
02380 {
02381 LASS_THROW("edges for delayed swapping found");
02382 }
02383 madeConstraint = true;
02384 break;
02385 }
02386 }
02387 }
02388
02389 if (toSwapEdges.size()>0)
02390 return insertEdge( iSegment, iLeftHandle, iRightHandle, iPointHandle, iForcePointHandle, makeDelaunay );
02391 if (!madeConstraint)
02392 {
02393 LASS_THROW("could not force constrained edge");
02394 }
02395 LASS_ASSERT( org(ea) == faa );
02396 return ea;
02397 }
02398
02399
02400 TEMPLATE_DEF
02401 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::insertPolygon( const TSimplePolygon2D& iPolygon, EdgeHandle iLeftHandle, EdgeHandle iRightHandle, bool makeDelaunay)
02402 {
02403 TEdge* e = NULL;
02404 for (size_t i=1;i<iPolygon.size();++i)
02405 {
02406 e=insertEdge(TLineSegment2D(iPolygon[i-1],iPolygon[i]),iLeftHandle,iRightHandle);
02407 }
02408 e=insertEdge(TLineSegment2D(iPolygon[iPolygon.size()-1],iPolygon[0]),iLeftHandle,iRightHandle);
02409 return e;
02410 }
02411
02412
02413 TEMPLATE_DEF
02414 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::markPolygon( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle = FaceHandle())
02415 {
02416 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
02417 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
02418 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
02419 TEdgeMarker edgeMarker( this, false );
02420 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
02421 #pragma LASS_TODO("do a more efficient marking or allow for multiple marking")
02422
02423 int n = chainOrder(iStartEdge);
02424 for (int i=0;i<n;++i)
02425 {
02426 floodPolygon( iStartEdge->sym(), iPolygon, iFaceHandle );
02427 iStartEdge = iStartEdge->lNext();
02428 }
02429 }
02430
02431
02432 TEMPLATE_DEF
02433 template <typename InputPolygonIterator, typename InputFaceHandleIterator>
02434 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::markPolygons( InputPolygonIterator iFirstPolygon, InputPolygonIterator iLastPolygon, InputFaceHandleIterator iFirstFaceHandle )
02435 {
02436 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
02437 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
02438 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
02439 TEdgeMarker edgeMarker( this, false );
02440 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
02441
02442 while (iFirstPolygon != iLastPolygon)
02443 {
02444 TEdge* iStartEdge = locate((*iFirstPolygon)[0]);
02445 int n = chainOrder(iStartEdge);
02446 for (int i=0;i<n;++i)
02447 {
02448 floodPolygon( iStartEdge->sym(), *iFirstPolygon, *iFirstFaceHandle );
02449 iStartEdge = iStartEdge->lNext();
02450 }
02451 ++iFirstPolygon;
02452 ++iFirstFaceHandle;
02453 }
02454 }
02455
02456
02457 TEMPLATE_DEF
02458 template <typename InputPolygonIterator, typename InputFaceHandleIterator>
02459 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllPolygonFaces( InputPolygonIterator iFirstPolygon, InputPolygonIterator iLastPolygon, InputFaceHandleIterator iFirstFaceHandle, const TEdgePolyFaceHandleCallback& iCallback )
02460 {
02461 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
02462 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
02463 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
02464 TEdgeMarker edgeMarker( this, false );
02465 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
02466
02467 while (iFirstPolygon != iLastPolygon)
02468 {
02469 TEdge* iStartEdge = locate((*iFirstPolygon)[0],*lastFloodEdge_);
02470 int n = chainOrder(iStartEdge);
02471 for (int i=0;i<n;++i)
02472 {
02473 if (!floodPolygonCallback( iStartEdge->sym(), *iFirstPolygon, *iFirstFaceHandle, iCallback ))
02474 {
02475 return false;
02476 }
02477 if (!floodPolygonCallback( iStartEdge, *iFirstPolygon, *iFirstFaceHandle, iCallback ))
02478 {
02479 return false;
02480 }
02481 iStartEdge = iStartEdge->lNext();
02482 }
02483 ++iFirstPolygon;
02484 ++iFirstFaceHandle;
02485 }
02486 std::cout << "Out polygon faces true" << std::endl;
02487 return true;
02488 }
02489
02490
02491
02492 TEMPLATE_DEF
02493 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::markPolygons( const std::vector<TSimplePolygon2D>& iPolygons, const std::vector<FaceHandle>& iFaceHandles)
02494 {
02495 if (iPolygons.size()!=iFaceHandles.size())
02496 {
02497 LASS_THROW("markPolygons: list of polygons must fit list of face handles");
02498 }
02499 markPolygons(iPolygons.begin(), iPolygons.end(), iFaceHandles.begin());
02500 }
02501
02502
02503 TEMPLATE_DEF
02504 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::floodPolygon( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle = FaceHandle())
02505 {
02506 TPoint2D bary = polygon(iStartEdge).surfaceCentroid().affine();
02507 if (iPolygon.contains(bary) && !internalMarking(iStartEdge))
02508 {
02509 setInternalMarking( iStartEdge, true );
02510 setFaceHandle( iStartEdge, iFaceHandle );
02511 int n = chainOrder(iStartEdge);
02512 for (int i=0;i<n;++i)
02513 {
02514 if (!floodPolygon( iStartEdge->sym(), iPolygon, iFaceHandle))
02515 return false;
02516 iStartEdge = iStartEdge->lNext();
02517 }
02518 }
02519 return true;
02520 }
02521
02522 TEMPLATE_DEF
02523 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::floodPolygonCallback( TEdge* iStartEdge, const TSimplePolygon2D& iPolygon, FaceHandle iFaceHandle, const TEdgePolyFaceHandleCallback& iCallback )
02524 {
02525 *lastFloodEdge_ = iStartEdge;
02526 bool r = true;
02527 TPoint2D bary = polygon(iStartEdge).surfaceCentroid().affine();
02528 if (iPolygon.contains(bary) && !internalMarking(iStartEdge))
02529 {
02530 setInternalMarking( iStartEdge, true );
02531 if (iCallback)
02532 if (!iCallback(iStartEdge, iPolygon,iFaceHandle))
02533 {
02534 return false;
02535 }
02536 int n = chainOrder(iStartEdge);
02537 for (int i=0;i<n;++i)
02538 {
02539 if (!floodPolygonCallback( iStartEdge->sym(), iPolygon, iFaceHandle, iCallback ))
02540 {
02541 return false;
02542 }
02543 iStartEdge = iStartEdge->lNext();
02544 }
02545 }
02546 return true;
02547 }
02548
02549 TEMPLATE_DEF
02550 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::makeEdge( const TPoint2D& a, const TPoint2D& b, bool makeConstrained )
02551 {
02552 TEdge* e(makeEmptyEdge( makeConstrained ));
02553
02554 TPoint2D* na = make(a);
02555 TPoint2D* nb = make(b);
02556 e->handle().point_ = na;
02557 e->sym()->handle().point_ = nb;
02558
02559 return e;
02560 }
02561
02562 TEMPLATE_DEF
02563 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TEdge* PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::startEdge() const
02564 {
02565 return startEdge_;
02566 }
02567
02568
02569 TEMPLATE_DEF
02570 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::inPrimaryMesh( const TEdge* iEdge )
02571 {
02572 return (iEdge->index() == 2) || (iEdge->index() == 0);
02573 }
02574
02575 TEMPLATE_DEF
02576 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::inDualMesh( const TEdge* iEdge )
02577 {
02578 return !inPrimaryMesh( iEdge );
02579 }
02580
02581 TEMPLATE_DEF
02582 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TTriangle2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::triangle( const TEdge* iEdge)
02583 {
02584 if (!inPrimaryMesh(iEdge))
02585 {
02586 LASS_THROW("PlanarMesh::triangle: edge not in primary mesh");
02587 }
02588 return TTriangle2D(org(iEdge),dest(iEdge),dest(iEdge->lNext()));
02589 }
02590
02591 TEMPLATE_DEF
02592 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TSimplePolygon2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::polygon( const TEdge* iEdge)
02593 {
02594 if (!inPrimaryMesh(iEdge))
02595 {
02596 LASS_THROW("PlanarMesh::polygon: edge not in primary mesh");
02597 }
02598 TSimplePolygon2D poly;
02599 const TEdge* cEdge = iEdge;
02600 do
02601 {
02602 poly.add(org(cEdge));
02603 cEdge = cEdge->lNext();
02604 } while (cEdge!=iEdge);
02605 return poly;
02606 }
02607
02608 TEMPLATE_DEF
02609 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::inConvexCell( const TPoint2D& iPoint, const TEdge* iEdge)
02610 {
02611 if (!inPrimaryMesh(iEdge))
02612 {
02613 LASS_THROW("PlanarMesh::polygon: edge not in primary mesh");
02614 }
02615 const TEdge* cEdge = iEdge;
02616 do
02617 {
02618 if (rightOf(iPoint, cEdge))
02619 return false;
02620 cEdge = cEdge->lNext();
02621 } while (cEdge!=iEdge);
02622 return true;
02623 }
02624
02625 TEMPLATE_DEF
02626 const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::org( const TEdge* iEdge )
02627 {
02628 if (!inPrimaryMesh( iEdge ))
02629 {
02630 LASS_THROW("PlanarMesh::org: edge not in primary mesh");
02631 }
02632 return *iEdge->handle().point_;
02633 }
02634
02635 TEMPLATE_DEF
02636 const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastOrg( const TEdge* iEdge )
02637 {
02638 return *iEdge->handle().point_;
02639 }
02640
02641 TEMPLATE_DEF
02642 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::along( const TEdge* iEdge, const T& iParam )
02643 {
02644 LASS_ASSERT(inPrimaryMesh( iEdge ));
02645
02646
02647
02648
02649
02650
02651 const TPoint2D& eOrg = *iEdge->handle().point_;
02652 const TPoint2D& eDest = *iEdge->sym()->handle().point_;
02653 const T oX = eDest.x*iParam + (T(1)-iParam)*eOrg.x;
02654 const T oY = eDest.y*iParam + (T(1)-iParam)*eOrg.y;
02655 return TPoint2D(oX,oY);
02656 }
02657
02658 TEMPLATE_DEF
02659 typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastAlong( const TEdge* iEdge, const T& iParam )
02660 {
02661 const TPoint2D& eOrg = *iEdge->handle()->point_;
02662 const TPoint2D& eDest = *iEdge->sym()->handle()->point_;
02663 const T oX = eDest.x*iParam + (T(1)-iParam)*eOrg.x;
02664 const T oY = eDest.y*iParam + (T(1)-iParam)*eOrg.y;
02665 return TPoint2D(oX,oY);
02666 }
02667
02668
02669 TEMPLATE_DEF inline
02670 const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::dest( const TEdge* iEdge )
02671 {
02672 return org( iEdge->sym() );
02673 }
02674
02675 TEMPLATE_DEF inline
02676 const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TPoint2D& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastDest( const TEdge* iEdge )
02677 {
02678 return fastOrg( iEdge->sym() );
02679 }
02680
02681 TEMPLATE_DEF inline
02682 const typename PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::TVector2D PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::direction( const TEdge* iEdge )
02683 {
02684 return dest( iEdge ) - org( iEdge );
02685 }
02686
02687 TEMPLATE_DEF
02688 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setOrg( const TPoint2D& iPoint, TEdge* iEdge )
02689 {
02690 LASS_ASSERT( inPrimaryMesh( iEdge ) );
02691 *iEdge->handle().point_ = iPoint;
02692 }
02693
02694 TEMPLATE_DEF
02695 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setDest( const TPoint2D& iPoint, TEdge* iEdge )
02696 {
02697 LASS_ASSERT( inPrimaryMesh( iEdge ) );
02698 *iEdge->sym()->handle().point_ = iPoint;
02699 }
02700
02701 TEMPLATE_DEF
02702 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::rightOf( const TPoint2D& iPoint, const TEdge* iEdge )
02703 {
02704 return lass::prim::ccw( iPoint, dest(iEdge), org(iEdge) );
02705 }
02706
02707 TEMPLATE_DEF
02708 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastRightOf( const TPoint2D& iPoint, const TEdge* iEdge )
02709 {
02710 return lass::prim::ccw( iPoint, fastDest(iEdge), fastOrg(iEdge) );
02711 }
02712
02713
02714 TEMPLATE_DEF
02715 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::leftOf( const TPoint2D& iPoint, const TEdge* iEdge )
02716 {
02717 return lass::prim::ccw( iPoint, org(iEdge), dest(iEdge) );
02718 }
02719
02720 TEMPLATE_DEF
02721 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastLeftOf( const TPoint2D& iPoint, const TEdge* iEdge )
02722 {
02723 return lass::prim::ccw( iPoint, fastOrg(iEdge), fastDest(iEdge) );
02724 }
02725
02726 TEMPLATE_DEF
02727 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::onEdge( const TPoint2D& iPoint, const TEdge* iEdge )
02728 {
02729 if (prim::doubleTriangleArea( iPoint, org(iEdge), dest(iEdge)) == T(0) )
02730 {
02731 TLineSegment2D eSeg(org(iEdge), dest(iEdge) );
02732 T rt = eSeg.t(iPoint);
02733 return (rt>=T(0)) && (rt<=T(1));
02734 }
02735 return false;
02736 }
02737 TEMPLATE_DEF
02738 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::hasLeftFace( const TEdge* e )
02739 {
02740
02741
02742
02743 return leftOf(dest(e->lNext()), e);
02744 }
02745
02746 TEMPLATE_DEF
02747 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::fastHasLeftFace( const TEdge* e )
02748 {
02749
02750
02751
02752 return fastLeftOf(fastDest(e->lNext()), e);
02753 }
02754
02755 TEMPLATE_DEF
02756 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::hasRightFace( const TEdge* iEdge )
02757 {
02758 return hasLeftFace( iEdge->sym() );
02759 }
02760
02761
02762
02763
02764
02765 TEMPLATE_DEF
02766 int PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::chainOrder( const TEdge* iEdge )
02767 {
02768 int order = 0;
02769 const TEdge* currentEdge = iEdge;
02770 do
02771 {
02772 ++order;
02773 currentEdge = currentEdge->lNext();
02774 } while (currentEdge!=iEdge);
02775 return order;
02776 }
02777
02778
02779
02780
02781
02782 TEMPLATE_DEF
02783 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::allEqualChainOrder( const TEdge* iEdge )
02784 {
02785 int chOrd = chainOrder(iEdge);
02786 for (int i=1;i<vertexOrder(iEdge);++i)
02787 {
02788 iEdge = iEdge->oNext();
02789 if (chainOrder(iEdge)!=chOrd)
02790 return false;
02791 }
02792 return true;
02793 }
02794
02795
02796
02797
02798
02799 TEMPLATE_DEF
02800 int PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::vertexOrder( const TEdge* iEdge )
02801 {
02802 int order = 0;
02803 const TEdge* currentEdge = iEdge;
02804 do
02805 {
02806 ++order;
02807 currentEdge = currentEdge->oNext();
02808 } while (currentEdge!=iEdge);
02809 return order;
02810 }
02811
02812
02813 TEMPLATE_DEF
02814 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::marking( const TEdge* iEdge )
02815 {
02816 return iEdge->handle().internalMark_[publicMarkIndex];
02817 }
02818
02819 TEMPLATE_DEF
02820 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::internalMarking( const TEdge* iEdge )
02821 {
02822 return iEdge->handle().internalMark_[stackDepth_];
02823 }
02824
02825
02826 TEMPLATE_DEF
02827 PointHandle PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::pointHandle( const TEdge* iEdge )
02828 {
02829 return inPrimaryMesh( iEdge ) ? iEdge->handle().pointHandle() : PointHandle();
02830 }
02831
02832 TEMPLATE_DEF
02833 EdgeHandle PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::edgeHandle( const TEdge* iEdge )
02834 {
02835 return inPrimaryMesh( iEdge ) ? iEdge->handle().edgeHandle() : EdgeHandle();
02836 }
02837
02838 TEMPLATE_DEF
02839 FaceHandle PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::faceHandle(const TEdge* iEdge )
02840 {
02841 if ( inPrimaryMesh( iEdge ) )
02842 {
02843 return iEdge->rot()->handle().faceHandle();
02844 }
02845 return FaceHandle();
02846 }
02847
02848
02849 TEMPLATE_DEF
02850 PointHandle& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::pointHandleRef( TEdge* iEdge )
02851 {
02852 if (inPrimaryMesh(iEdge))
02853 return iEdge->handle().pointHandle();
02854 LASS_THROW("no point handle available");
02855 }
02856
02857 TEMPLATE_DEF
02858 EdgeHandle& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::edgeHandleRef( TEdge* iEdge )
02859 {
02860 if (inPrimaryMesh(iEdge))
02861 return iEdge->handle().edgeHandle();
02862 LASS_THROW("no edge handle available");
02863 }
02864
02865 TEMPLATE_DEF
02866 FaceHandle& PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::faceHandleRef( TEdge* iEdge )
02867 {
02868 if ( inPrimaryMesh( iEdge ) )
02869 {
02870 return iEdge->rot()->handle().faceHandle();
02871 }
02872 LASS_THROW("no face handle available");
02873 }
02874
02875 TEMPLATE_DEF
02876 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setMarking( TEdge* iEdge, bool iMark )
02877 {
02878 iEdge->handle().internalMark_.set(publicMarkIndex, iMark);
02879 }
02880
02881 TEMPLATE_DEF
02882 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setInternalMarking( TEdge* iEdge, bool iMark )
02883 {
02884 iEdge->handle().internalMark_.set(stackDepth_, iMark);
02885 }
02886
02887 TEMPLATE_DEF
02888 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setInternalMarkingAroundVertex( TEdge* iEdge, bool iMark )
02889 {
02890 TEdge* e = iEdge;
02891 do
02892 {
02893 setInternalMarking( e, iMark );
02894 e = e->oNext();
02895 } while (e!=iEdge);
02896 }
02897
02898 TEMPLATE_DEF
02899 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setInternalMarkingInFace( TEdge* iEdge, bool iMark )
02900 {
02901 TEdge* e = iEdge;
02902 do
02903 {
02904 setInternalMarking( e, iMark );
02905 e = e->lNext();
02906 } while (e!=iEdge);
02907 }
02908
02909
02910 TEMPLATE_DEF
02911 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setPointHandle( TEdge* iEdge, PointHandle iHandle )
02912 {
02913 if (! inPrimaryMesh( iEdge ) )
02914 throw std::runtime_error("setPointHandle : edge not in primary mesh");
02915
02916 TEdge* currentEdge = iEdge;
02917 do
02918 {
02919 currentEdge->handle().pointHandle() = iHandle;
02920 currentEdge = currentEdge->oNext();
02921 } while ( currentEdge != iEdge );
02922 }
02923
02924 TEMPLATE_DEF
02925 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setEdgeHandle( TEdge* iEdge, EdgeHandle iHandle )
02926 {
02927 if (! inPrimaryMesh( iEdge ) )
02928 throw std::runtime_error("setEdgeHandle : edge not in primary mesh");
02929 iEdge->handle().edgeHandle() = iHandle;
02930 }
02931
02932 TEMPLATE_DEF
02933 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setFaceHandle( TEdge* iEdge, FaceHandle iHandle )
02934 {
02935 if (! inPrimaryMesh( iEdge ) )
02936 throw std::runtime_error("setFaceHandle : edge not in dual mesh");
02937
02938 TEdge* currentEdge = iEdge;
02939 do
02940 {
02941 currentEdge->rot()->handle().faceHandle() = iHandle;
02942 if ( faceHandle( currentEdge ) != faceHandle( currentEdge->sym() ) )
02943 currentEdge->quadEdge()->faceConstrain();
02944 else
02945 currentEdge->quadEdge()->faceDeconstrain();
02946 currentEdge = currentEdge->lNext();
02947 } while ( currentEdge != iEdge );
02948 }
02949
02950 TEMPLATE_DEF
02951 void PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::setOrientedEdgeHandle(
02952 TEdge* iEdge, EdgeHandle iLeftHandle, EdgeHandle iRightHandle, const TVector2D& iOrientation )
02953 {
02954 #ifndef NDEBUG
02955 ++numSetOrientedEdgeHandleCalls;
02956 #endif
02957 if (prim::dot(direction(iEdge), iOrientation) < T(0))
02958 {
02959 #ifndef NDEBUG
02960 ++numSetOrientedEdgeHandleSwaps;
02961 #endif
02962 std::swap(iLeftHandle, iRightHandle);
02963 }
02964 setEdgeHandle(iEdge, iLeftHandle);
02965 setEdgeHandle(iEdge->sym(), iRightHandle);
02966 }
02967
02968 TEMPLATE_DEF
02969 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllPrimaryEdges( const TEdgeCallback& iCallback )
02970 {
02971 typename TQuadEdgeList::iterator qIt;
02972 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
02973 {
02974 if (!(*qIt)->deleted)
02975 {
02976 if (inPrimaryMesh( (*qIt)->edges() ) )
02977 {
02978 if (!iCallback( (*qIt)->edges() )) return false;
02979 if (!iCallback( (*qIt)->edges()->sym() )) return false;
02980 }
02981 else
02982 {
02983 if (!iCallback( (*qIt)->edges()->rot() )) return false;
02984 if (!iCallback( (*qIt)->edges()->invRot() )) return false;
02985 }
02986 }
02987 }
02988 return true;
02989 }
02990
02991
02992 TEMPLATE_DEF
02993 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllPrimaryUndirectedEdges( const TEdgeCallback& iCallback )
02994 {
02995 typename TQuadEdgeList::iterator qIt;
02996 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
02997 {
02998 if (!(*qIt)->deleted)
02999 {
03000 if (inPrimaryMesh( (*qIt)->edges() ) )
03001 {
03002 if (!iCallback( (*qIt)->edges() )) return false;
03003 }
03004 else
03005 {
03006 if (!iCallback( (*qIt)->edges()->rot() )) return false;
03007 }
03008 }
03009 }
03010 return true;
03011 }
03012
03013 TEMPLATE_DEF
03014 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllPrimaryUndirectedEdgesCached( const TEdgeCallback& iCallback )
03015 {
03016 typename TQuadEdgeList::iterator qIt;
03017 static size_t start = 0;
03018 size_t savedStart = start;
03019
03020 if (savedStart>quadEdgeList_.size()-1)
03021 {
03022 savedStart = 0;
03023 start = 0;
03024 }
03025
03026 for (size_t i = savedStart; i<quadEdgeList_.size();++i)
03027 {
03028 TQuadEdge* qe = quadEdgeList_[i];
03029 if (!qe->deleted)
03030 {
03031 if (inPrimaryMesh( (qe)->edges() ) )
03032 {
03033 if (!iCallback( (qe)->edges() )) return false;
03034 }
03035 else
03036 {
03037 if (!iCallback( (qe)->edges()->rot() )) return false;
03038 }
03039 }
03040 ++start;
03041 }
03042 start = 0;
03043 for (size_t i = 0; i<savedStart;++i)
03044 {
03045 TQuadEdge* qe = quadEdgeList_[i];
03046 if (!qe->deleted)
03047 {
03048 if (inPrimaryMesh( (qe)->edges() ) )
03049 {
03050 if (!iCallback( (qe)->edges() )) return false;
03051 }
03052 else
03053 {
03054 if (!iCallback( (qe)->edges()->rot() )) return false;
03055 }
03056 }
03057 ++start;
03058 }
03059 return true;
03060 }
03061
03062 TEMPLATE_DEF
03063 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllDualEdges( const TEdgeCallback& iCallback )
03064 {
03065 typename TQuadEdgeList::iterator qIt;
03066 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
03067 {
03068 if (!(*qIt)->deleted)
03069 {
03070 if (inDualMesh( (*qIt)->edges() ) )
03071 {
03072 if (!iCallback( (*qIt)->edges() )) return false;
03073 if (!iCallback( (*qIt)->edges()->sym() )) return false;
03074 }
03075 else
03076 {
03077 if (!iCallback( (*qIt)->edges()->rot() )) return false;
03078 if (!iCallback( (*qIt)->edges()->invRot() )) return false;
03079 }
03080 }
03081 }
03082 return true;
03083 }
03084
03085 TEMPLATE_DEF
03086 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllEdges( const TEdgeCallback& iCallback )
03087 {
03088 typename TQuadEdgeList::iterator qIt;
03089 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
03090 {
03091 if (!(*qIt)->deleted)
03092 {
03093 if (!iCallback( (*qIt)->edges() )) return false;
03094 if (!iCallback( (*qIt)->edges()->sym() )) return false;
03095 if (!iCallback( (*qIt)->edges()->rot() )) return false;
03096 if (!iCallback( (*qIt)->edges()->invRot() )) return false;
03097 }
03098 }
03099 return true;
03100 }
03101
03102 TEMPLATE_DEF
03103 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllVertices( const TEdgeCallback& iCallback )
03104 {
03105 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
03106 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
03107 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
03108 TEdgeMarker edgeMarker( this, false );
03109 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
03110
03111 typename TQuadEdgeList::iterator qIt;
03112 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
03113 {
03114 if (!(*qIt)->deleted)
03115 {
03116 TEdge* baseEdge = (*qIt)->edges();
03117 if (inDualMesh( baseEdge ) )
03118 baseEdge = baseEdge->rot();
03119
03120 TEdge* e = baseEdge;
03121 for (int i=0;i<2;++i)
03122 {
03123 if ( !internalMarking( e ) )
03124 {
03125 if (!iCallback( e ))
03126 return false;
03127 setInternalMarkingAroundVertex( e, true );
03128 }
03129 e = e->sym();
03130 }
03131 }
03132 }
03133 return true;
03134 }
03135
03136 TEMPLATE_DEF
03137 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllFacesCached( const TEdgeCallback& iCallback )
03138 {
03139 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
03140 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
03141 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
03142 TEdgeMarker edgeMarker( this, false );
03143 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
03144
03145 static size_t startFace = 0;
03146 size_t savedStart = startFace;
03147
03148 if (savedStart>quadEdgeList_.size()-1)
03149 {
03150 savedStart = 0;
03151 startFace = 0;
03152 }
03153
03154 for (size_t i = savedStart; i<quadEdgeList_.size();++i)
03155 {
03156 startFace = i;
03157 TQuadEdge* qe = quadEdgeList_[i];
03158 if (!qe->deleted)
03159 {
03160 TEdge* baseEdge = qe->edges();
03161 if (inDualMesh( baseEdge ) )
03162 baseEdge = baseEdge->rot();
03163
03164 TEdge* e = baseEdge;
03165 for (int i=0;i<2;++i)
03166 {
03167 if ( !internalMarking( e ) )
03168 {
03169 if (!iCallback( e ))
03170 return false;
03171 setInternalMarkingInFace( e, true );
03172 }
03173 e = e->sym();
03174 }
03175 }
03176 }
03177 for (size_t i = 0; i<savedStart;++i)
03178 {
03179 startFace = i;
03180 TQuadEdge* qe = quadEdgeList_[i];
03181 if (!qe->deleted)
03182 {
03183 TEdge* baseEdge = qe->edges();
03184 if (inDualMesh( baseEdge ) )
03185 baseEdge = baseEdge->rot();
03186
03187 TEdge* e = baseEdge;
03188 for (int i=0;i<2;++i)
03189 {
03190 if ( !internalMarking( e ) )
03191 {
03192 if (!iCallback( e ))
03193 return false;
03194 setInternalMarkingInFace( e, true );
03195 }
03196 e = e->sym();
03197 }
03198 }
03199 }
03200 return true;
03201 }
03202
03203 TEMPLATE_DEF
03204 bool PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::forAllFaces( const TEdgeCallback& iCallback )
03205 {
03206 StackIncrementer( &stackDepth_, PLANAR_MESH_STACK_DEPTH );
03207 typedef PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle> TPlanarMesh;
03208 typedef impl::EdgeMarker<T, PointHandle, EdgeHandle, FaceHandle> TEdgeMarker;
03209 TEdgeMarker edgeMarker( this, false );
03210 forAllPrimaryEdges( TEdgeCallback( &edgeMarker, &TEdgeMarker::internalMark ) );
03211
03212 typename TQuadEdgeList::iterator qIt;
03213 for (qIt = quadEdgeList_.begin(); qIt != quadEdgeList_.end();++qIt)
03214 {
03215 if (!(*qIt)->deleted)
03216 {
03217 TEdge* baseEdge = (*qIt)->edges();
03218 if (inDualMesh( baseEdge ) )
03219 baseEdge = baseEdge->rot();
03220
03221 TEdge* e = baseEdge;
03222 for (int i=0;i<2;++i)
03223 {
03224 if ( !internalMarking( e ) )
03225 {
03226 if (!iCallback( e ))
03227 return false;
03228 setInternalMarkingInFace( e, true );
03229 }
03230 e = e->sym();
03231 }
03232 }
03233 }
03234 return true;
03235 }
03236
03237
03238 #ifndef NDEBUG
03239 TEMPLATE_DEF unsigned PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::numSetOrientedEdgeHandleCalls = 0;
03240 TEMPLATE_DEF unsigned PlanarMesh<T, PointHandle, EdgeHandle, FaceHandle>::numSetOrientedEdgeHandleSwaps = 0;
03241 #endif
03242
03243
03244 }
03245
03246 }
03247
03248 #endif