0029701: BRepTools::Update(Face) unexpectedly updates UV points of pcurve
[occt.git] / src / BRepTools / BRepTools.cxx
old mode 100755 (executable)
new mode 100644 (file)
index f77dea8..6a1096f
-// File:        BRepTools.cxx
-// Created:     Thu Jan 21 19:59:19 1993
-// Author:      Remi LEQUETTE
-//              <rle@phylox>
+// Created on: 1993-01-21
+// Created by: Remi LEQUETTE
+// Copyright (c) 1993-1999 Matra Datavision
+// Copyright (c) 1999-2014 OPEN CASCADE SAS
+//
+// This file is part of Open CASCADE Technology software library.
+//
+// This library is free software; you can redistribute it and/or modify it under
+// the terms of the GNU Lesser General Public License version 2.1 as published
+// by the Free Software Foundation, with special exception defined in the file
+// OCCT_LGPL_EXCEPTION.txt. Consult the file LICENSE_LGPL_21.txt included in OCCT
+// distribution for complete text of the license and disclaimer of any warranty.
+//
+// Alternatively, this file may be used under the terms of Open CASCADE
+// commercial license or contractual agreement.
 
-#include <Standard_Stream.hxx>
 
-#include <BRepTools.ixx>
-#include <BRepTools_ShapeSet.hxx>
-#include <BRep_Tool.hxx>
-#include <TopExp.hxx>
-#include <TopExp_Explorer.hxx>
-#include <TopoDS.hxx>
-#include <TopoDS_Iterator.hxx>
+#include <Bnd_Box2d.hxx>
 #include <BndLib_Add2dCurve.hxx>
-#include <Geom2dAdaptor_Curve.hxx>
-#include <Geom_Surface.hxx>
-#include <Geom_Curve.hxx>
-#include <Geom2d_Curve.hxx>
-#include <BRepTools_MapOfVertexPnt2d.hxx>
+#include <BRep_Builder.hxx>
 #include <BRep_CurveRepresentation.hxx>
-#include <BRep_ListIteratorOfListOfCurveRepresentation.hxx>
+#include <BRep_GCurve.hxx>
+#include <BRep_ListOfCurveRepresentation.hxx>
 #include <BRep_TEdge.hxx>
+#include <BRep_Tool.hxx>
+#include <BRepTools.hxx>
+#include <BRepTools_MapOfVertexPnt2d.hxx>
+#include <BRepTools_ShapeSet.hxx>
+#include <BRepAdaptor_Surface.hxx>
+#include <ElCLib.hxx>
+#include <Geom2d_Curve.hxx>
+#include <Geom2dAdaptor_Curve.hxx>
+#include <Geom_BSplineSurface.hxx>
+#include <Geom_Curve.hxx>
+#include <Geom_RectangularTrimmedSurface.hxx>
+#include <Geom_Surface.hxx>
+#include <gp_Lin2d.hxx>
+#include <gp_Vec2d.hxx>
+#include <Message_ProgressIndicator.hxx>
+#include <OSD_OpenFile.hxx>
+#include <Poly_PolygonOnTriangulation.hxx>
+#include <Poly_Triangulation.hxx>
+#include <Precision.hxx>
+#include <Standard_ErrorHandler.hxx>
+#include <Standard_Failure.hxx>
+#include <Standard_Stream.hxx>
+#include <TColGeom2d_SequenceOfCurve.hxx>
 #include <TColgp_SequenceOfPnt2d.hxx>
+#include <TColStd_Array1OfReal.hxx>
+#include <TColStd_HArray1OfInteger.hxx>
+#include <TColStd_MapOfTransient.hxx>
 #include <TColStd_SequenceOfReal.hxx>
-#include <TColGeom2d_SequenceOfCurve.hxx>
+#include <TopExp.hxx>
+#include <TopExp_Explorer.hxx>
+#include <TopoDS.hxx>
+#include <TopoDS_Compound.hxx>
+#include <TopoDS_CompSolid.hxx>
+#include <TopoDS_Edge.hxx>
+#include <TopoDS_Face.hxx>
+#include <TopoDS_Iterator.hxx>
+#include <TopoDS_Shape.hxx>
+#include <TopoDS_Shell.hxx>
+#include <TopoDS_Solid.hxx>
+#include <TopoDS_Vertex.hxx>
+#include <TopoDS_Wire.hxx>
 #include <TopTools_SequenceOfShape.hxx>
-#include <Precision.hxx>
+#include <GeomLib_CheckCurveOnSurface.hxx>
+#include <errno.h>
 
-#include <Poly_Triangulation.hxx>
-#include <Poly_PolygonOnTriangulation.hxx>
-#include <TColStd_HArray1OfInteger.hxx>
 
-#include <gp_Lin2d.hxx>
-#include <ElCLib.hxx>
-#include <gp_Vec2d.hxx>
-#include <Standard_ErrorHandler.hxx>
-#include <Standard_Failure.hxx>
+//=======================================================================
+//function : IsPCurveUiso
+//purpose  : 
+//=======================================================================
+
+static Standard_Boolean IsPCurveUiso(const Handle(Geom2d_Curve)& thePCurve,
+                                     Standard_Real theFirstPar,
+                                     Standard_Real theLastPar)
+{
+  gp_Pnt2d FirstP2d = thePCurve->Value(theFirstPar);
+  gp_Pnt2d LastP2d  = thePCurve->Value(theLastPar);
+
+  Standard_Real DeltaU = Abs(FirstP2d.X() - LastP2d.X());
+  Standard_Real DeltaV = Abs(FirstP2d.Y() - LastP2d.Y());
+
+  return (DeltaU < DeltaV);
+}
 
-#include <errno.h>
 
 //=======================================================================
 //function : UVBounds
 //purpose  : 
 //=======================================================================
-
 void  BRepTools::UVBounds(const TopoDS_Face& F, 
                           Standard_Real& UMin, Standard_Real& UMax, 
                           Standard_Real& VMin, Standard_Real& VMax)
 {
   Bnd_Box2d B;
   AddUVBounds(F,B);
-  B.Get(UMin,VMin,UMax,VMax);
+  if (!B.IsVoid())
+  {
+    B.Get(UMin,VMin,UMax,VMax);
+  }
+  else
+  {
+    UMin = UMax = VMin = VMax = 0.0;
+  }
 }
 
 //=======================================================================
@@ -65,7 +119,14 @@ void  BRepTools::UVBounds(const TopoDS_Face& F,
 {
   Bnd_Box2d B;
   AddUVBounds(F,W,B);
-  B.Get(UMin,VMin,UMax,VMax);
+  if (!B.IsVoid())
+  {
+    B.Get(UMin,VMin,UMax,VMax);
+  }
+  else
+  {
+    UMin = UMax = VMin = VMax = 0.0;
+  }
 }
 
 
@@ -81,7 +142,14 @@ void  BRepTools::UVBounds(const TopoDS_Face& F,
 {
   Bnd_Box2d B;
   AddUVBounds(F,E,B);
-  B.Get(UMin,VMin,UMax,VMax);
+  if (!B.IsVoid())
+  {
+    B.Get(UMin,VMin,UMax,VMax);
+  }
+  else
+  {
+    UMin = UMax = VMin = VMax = 0.0;
+  }
 }
 
 //=======================================================================
@@ -106,7 +174,13 @@ void  BRepTools::AddUVBounds(const TopoDS_Face& FF, Bnd_Box2d& B)
   if (aBox.IsVoid()) {
     Standard_Real UMin,UMax,VMin,VMax;
     TopLoc_Location L;
-    BRep_Tool::Surface(F,L)->Bounds(UMin,UMax,VMin,VMax);
+    const Handle(Geom_Surface)& aSurf = BRep_Tool::Surface(F, L);
+    if (aSurf.IsNull())
+    {
+      return;
+    }
+
+    aSurf->Bounds(UMin,UMax,VMin,VMax);
     aBox.Update(UMin,VMin,UMax,VMax);
   }
   
@@ -119,7 +193,6 @@ void  BRepTools::AddUVBounds(const TopoDS_Face& FF, Bnd_Box2d& B)
 //function : AddUVBounds
 //purpose  : 
 //=======================================================================
-
 void  BRepTools::AddUVBounds(const TopoDS_Face& F, 
                              const TopoDS_Wire& W, 
                              Bnd_Box2d& B)
@@ -135,88 +208,202 @@ void  BRepTools::AddUVBounds(const TopoDS_Face& F,
 //function : AddUVBounds
 //purpose  : 
 //=======================================================================
-
-void  BRepTools::AddUVBounds(const TopoDS_Face& F, 
-                             const TopoDS_Edge& E,
-                             Bnd_Box2d& B)
+void BRepTools::AddUVBounds(const TopoDS_Face& aF, 
+                            const TopoDS_Edge& aE,
+                            Bnd_Box2d& aB)
 {
-  Standard_Real pf,pl;
-  Bnd_Box2d Baux; 
-  const Handle(Geom2d_Curve) C = BRep_Tool::CurveOnSurface(E,F,pf,pl);
-  if (pl < pf) { // Petit Blindage
-    Standard_Real aux;
-    aux = pf; pf = pl; pl = aux;
-  }
-  if (C.IsNull()) return;
-  Geom2dAdaptor_Curve PC(C,pf,pl);
-  if (Precision::IsNegativeInfinite(pf) ||
-      Precision::IsPositiveInfinite(pf)) {
-    Geom2dAdaptor_Curve GC(PC);
-    BndLib_Add2dCurve::Add(GC,0.,B);
+  Standard_Real aT1, aT2, aXmin = 0.0, aYmin = 0.0, aXmax = 0.0, aYmax = 0.0;
+  Standard_Real aUmin, aUmax, aVmin, aVmax;
+  Bnd_Box2d aBoxC, aBoxS; 
+  TopLoc_Location aLoc;
+  //
+  const Handle(Geom2d_Curve) aC2D = BRep_Tool::CurveOnSurface(aE, aF, aT1, aT2);
+  if (aC2D.IsNull()) {
+    return;
+  }
+  //
+  BndLib_Add2dCurve::Add(aC2D, aT1, aT2, 0., aBoxC);
+  if (!aBoxC.IsVoid())
+  {
+    aBoxC.Get(aXmin, aYmin, aXmax, aYmax);
+  }
+  //
+  Handle(Geom_Surface) aS = BRep_Tool::Surface(aF, aLoc);
+  aS->Bounds(aUmin, aUmax, aVmin, aVmax);
+
+  if(aS->DynamicType() == STANDARD_TYPE(Geom_RectangularTrimmedSurface))
+  {
+    const Handle(Geom_RectangularTrimmedSurface) aSt = 
+                Handle(Geom_RectangularTrimmedSurface)::DownCast(aS);
+    aS = aSt->BasisSurface();
+  }
+
+  //
+  if(!aS->IsUPeriodic())
+  {
+    Standard_Boolean isUPeriodic = Standard_False;
+
+    // Additional verification for U-periodicity for B-spline surfaces
+    // 1. Verify that the surface is U-closed (if such flag is false). Verification uses 2 points
+    // 2. Verify periodicity of surface inside UV-bounds of the edge. Verification uses 3 or 6 points.
+    if (aS->DynamicType() == STANDARD_TYPE(Geom_BSplineSurface) &&
+        (aXmin < aUmin || aXmax > aUmax))
+    {
+      Standard_Real aTol2 = 100 * Precision::Confusion() * Precision::Confusion();
+      isUPeriodic = Standard_True;
+      gp_Pnt P1, P2;
+      // 1. Verify that the surface is U-closed
+      if (!aS->IsUClosed())
+      {
+        Standard_Real aVStep = aVmax - aVmin;
+        for (Standard_Real aV = aVmin; aV <= aVmax; aV += aVStep)
+        {
+          P1 = aS->Value(aUmin, aV);
+          P2 = aS->Value(aUmax, aV);
+          if (P1.SquareDistance(P2) > aTol2)
+          {
+            isUPeriodic = Standard_False;
+            break;
+          }
+        }
+      }
+      // 2. Verify periodicity of surface inside UV-bounds of the edge
+      if (isUPeriodic) // the flag still not changed
+      {
+        Standard_Real aV = (aVmin + aVmax) * 0.5;
+        Standard_Real aU[6]; // values of U lying out of surface boundaries
+        Standard_Real aUpp[6]; // corresponding U-values plus/minus period
+        Standard_Integer aNbPnt = 0;
+        if (aXmin < aUmin)
+        {
+          aU[0] = aXmin;
+          aU[1] = (aXmin + aUmin) * 0.5;
+          aU[2] = aUmin;
+          aUpp[0] = aU[0] + aUmax - aUmin;
+          aUpp[1] = aU[1] + aUmax - aUmin;
+          aUpp[2] = aU[2] + aUmax - aUmin;
+          aNbPnt += 3;
+        }
+        if (aXmax > aUmax)
+        {
+          aU[aNbPnt]     = aUmax;
+          aU[aNbPnt + 1] = (aXmax + aUmax) * 0.5;
+          aU[aNbPnt + 2] = aXmax;
+          aUpp[aNbPnt]     = aU[aNbPnt] - aUmax + aUmin;
+          aUpp[aNbPnt + 1] = aU[aNbPnt + 1] - aUmax + aUmin;
+          aUpp[aNbPnt + 2] = aU[aNbPnt + 2] - aUmax + aUmin;
+          aNbPnt += 3;
+        }
+        for (Standard_Integer anInd = 0; anInd < aNbPnt; anInd++)
+        {
+          P1 = aS->Value(aU[anInd], aV);
+          P2 = aS->Value(aUpp[anInd], aV);
+          if (P1.SquareDistance(P2) > aTol2)
+          {
+            isUPeriodic = Standard_False;
+            break;
+          }
+        }
+      }
     }
-  else {
 
-    // just compute points to get a close box.
-    TopLoc_Location L;
-    Standard_Real Umin,Umax,Vmin,Vmax;
-    const Handle(Geom_Surface)& Surf=BRep_Tool::Surface(F,L);
-    Surf->Bounds(Umin,Umax,Vmin,Vmax);
-    gp_Pnt2d Pa,Pb,Pc;
-
-
-    Standard_Real i, nbp = 20;
-    if (PC.GetType() == GeomAbs_Line) nbp = 2;
-    Standard_Real step = (pl - pf) / nbp;
-    gp_Pnt2d P;
-    PC.D0(pf,P);
-    Baux.Add(P);
-
-    Standard_Real du=0.0;
-    Standard_Real dv=0.0;
-
-    Pc=P;
-    for (i = 1; i < nbp; i++) {
-      pf += step;
-      PC.D0(pf,P);
-      Baux.Add(P);
-      if(i==1) { Pb=Pc; Pc=P; } 
-      else { 
-        //-- Calcul de la fleche 
-        Pa=Pb; Pb=Pc; Pc=P;     
-        gp_Vec2d PaPc(Pa,Pc);
-//      gp_Lin2d L2d(Pa,PaPc);
-//      Standard_Real up = ElCLib::Parameter(L2d,Pb);
-//      gp_Pnt2d PProj   = ElCLib::Value(up,L2d);
-        gp_Pnt2d PProj(Pa.Coord()+(PaPc.XY()/2.));
-        Standard_Real ddu=Abs(Pb.X()-PProj.X());
-        Standard_Real ddv=Abs(Pb.Y()-PProj.Y());
-        if(ddv>dv) dv=ddv;
-        if(ddu>du) du=ddu;
+    if (!isUPeriodic)
+    {
+      if((aXmin<aUmin) && (aUmin < aXmax))
+      {
+        aXmin=aUmin;
+      }
+      if((aXmin < aUmax) && (aUmax < aXmax))
+      {
+        aXmax=aUmax;
       }
     }
-    PC.D0(pl,P);
-    Baux.Add(P);
-
-    //-- cout<<" du="<<du<<"   dv="<<dv<<endl;
-    Standard_Real u0,u1,v0,v1;
-    Baux.Get(u0,v0,u1,v1);
-    du*=1.5;
-    dv*=1.5;
-    u0-=du; v0-=dv; u1+=du; v1+=dv;
-    if(Surf->IsUPeriodic()) { } 
-    else { 
-      if(u0<=Umin) {  u0=Umin; } 
-      if(u1>=Umax) {  u1=Umax; } 
+  }
+
+  if(!aS->IsVPeriodic())
+  {
+    Standard_Boolean isVPeriodic = Standard_False;
+
+    // Additional verification for V-periodicity for B-spline surfaces
+    // 1. Verify that the surface is V-closed (if such flag is false). Verification uses 2 points
+    // 2. Verify periodicity of surface inside UV-bounds of the edge. Verification uses 3 or 6 points.
+    if (aS->DynamicType() == STANDARD_TYPE(Geom_BSplineSurface) &&
+        (aYmin < aVmin || aYmax > aVmax))
+    {
+      Standard_Real aTol2 = 100 * Precision::Confusion() * Precision::Confusion();
+      isVPeriodic = Standard_True;
+      gp_Pnt P1, P2;
+      // 1. Verify that the surface is V-closed
+      if (!aS->IsVClosed())
+      {
+        Standard_Real aUStep = aUmax - aUmin;
+        for (Standard_Real aU = aUmin; aU <= aUmax; aU += aUStep)
+        {
+          P1 = aS->Value(aU, aVmin);
+          P2 = aS->Value(aU, aVmax);
+          if (P1.SquareDistance(P2) > aTol2)
+          {
+            isVPeriodic = Standard_False;
+            break;
+          }
+        }
+      }
+      // 2. Verify periodicity of surface inside UV-bounds of the edge
+      if (isVPeriodic) // the flag still not changed
+      {
+        Standard_Real aU = (aUmin + aUmax) * 0.5;
+        Standard_Real aV[6]; // values of V lying out of surface boundaries
+        Standard_Real aVpp[6]; // corresponding V-values plus/minus period
+        Standard_Integer aNbPnt = 0;
+        if (aYmin < aVmin)
+        {
+          aV[0] = aYmin;
+          aV[1] = (aYmin + aVmin) * 0.5;
+          aV[2] = aVmin;
+          aVpp[0] = aV[0] + aVmax - aVmin;
+          aVpp[1] = aV[1] + aVmax - aVmin;
+          aVpp[2] = aV[2] + aVmax - aVmin;
+          aNbPnt += 3;
+        }
+        if (aYmax > aVmax)
+        {
+          aV[aNbPnt]     = aVmax;
+          aV[aNbPnt + 1] = (aYmax + aVmax) * 0.5;
+          aV[aNbPnt + 2] = aYmax;
+          aVpp[aNbPnt]     = aV[aNbPnt] - aVmax + aVmin;
+          aVpp[aNbPnt + 1] = aV[aNbPnt + 1] - aVmax + aVmin;
+          aVpp[aNbPnt + 2] = aV[aNbPnt + 2] - aVmax + aVmin;
+          aNbPnt += 3;
+        }
+        for (Standard_Integer anInd = 0; anInd < aNbPnt; anInd++)
+        {
+          P1 = aS->Value(aU, aV[anInd]);
+          P2 = aS->Value(aU, aVpp[anInd]);
+          if (P1.SquareDistance(P2) > aTol2)
+          {
+            isVPeriodic = Standard_False;
+            break;
+          }
+        }
+      }
     }
-    if(Surf->IsVPeriodic()) { } 
-    else { 
-      if(v0<=Vmin) {  v0=Vmin; } 
-      if(v1>=Vmax) {  v1=Vmax; }
+
+    if (!isVPeriodic)
+    {
+      if((aYmin<aVmin) && (aVmin < aYmax))
+      {
+        aYmin=aVmin;
+      }
+      if((aYmin < aVmax) && (aVmax < aYmax))
+      {
+        aYmax=aVmax;
+      }
     }
-    P.SetCoord(u0,v0) ; Baux.Add(P);
-    P.SetCoord(u1,v1) ; Baux.Add(P);
-    B.Add(Baux);
   }
+  
+  aBoxS.Update(aXmin, aYmin, aXmax, aYmax);
+  
+  aB.Add(aBoxS);
 }
 
 //=======================================================================
@@ -362,132 +549,45 @@ void BRepTools::Update(const TopoDS_Shape& S)
   }
 }
 
-
 //=======================================================================
 //function : UpdateFaceUVPoints
-//purpose  : reset the UV points of a  Face
+//purpose  : Reset the UV points of edges on the Face
 //=======================================================================
-
-void  BRepTools::UpdateFaceUVPoints(const TopoDS_Face& F)
+void  BRepTools::UpdateFaceUVPoints(const TopoDS_Face& theF)
 {
-  // Recompute for each edge the two UV points in order to have the same
-  // UV point on connected edges.
+  // For each edge of the face <F> reset the UV points to the bounding
+  // points of the parametric curve of the edge on the face.
+
+  // Get surface of the face
+  TopLoc_Location aLoc;
+  const Handle(Geom_Surface)& aSurf = BRep_Tool::Surface(theF, aLoc);
+  // Iterate on edges and reset UV points
+  TopExp_Explorer anExpE(theF, TopAbs_EDGE);
+  for (; anExpE.More(); anExpE.Next())
+  {
+    const TopoDS_Edge& aE = TopoDS::Edge(anExpE.Current());
 
-  // First edge loop, store the vertices in a Map with their 2d points
+    const Handle(BRep_TEdge)& TE = *((Handle(BRep_TEdge)*)&aE.TShape());
+    if (TE->Locked())
+      return;
 
-  BRepTools_MapOfVertexPnt2d theVertices;
-  TopoDS_Iterator expE,expV;
-  TopoDS_Iterator EdgeIt,VertIt;
-  TColStd_SequenceOfReal aFSeq, aLSeq;
-  TColGeom2d_SequenceOfCurve aCSeq;
-  TopTools_SequenceOfShape aShSeq;
-  gp_Pnt2d P;
-  Standard_Integer i;
-  // a 3d tolerance for UV !!
-  Standard_Real tolerance = BRep_Tool::Tolerance(F);
-  TColgp_SequenceOfPnt2d emptySequence;
-  
-  for (expE.Initialize(F); expE.More(); expE.Next()) {
-    if(expE.Value().ShapeType() != TopAbs_WIRE)
-      continue;
-    
-    EdgeIt.Initialize(expE.Value());
-    for( ; EdgeIt.More(); EdgeIt.Next())
+    const TopLoc_Location aELoc = aLoc.Predivided(aE.Location());
+    // Edge representations
+    BRep_ListOfCurveRepresentation& aLCR = TE->ChangeCurves();
+    BRep_ListIteratorOfListOfCurveRepresentation itLCR(aLCR);
+    for (; itLCR.More(); itLCR.Next())
     {
-      const TopoDS_Edge& E = TopoDS::Edge(EdgeIt.Value());
-      Standard_Real f,l;
-      Handle(Geom2d_Curve) C = BRep_Tool::CurveOnSurface(E,F,f,l);
-
-      aFSeq.Append(f);
-      aLSeq.Append(l);
-      aCSeq.Append(C);
-      aShSeq.Append(E);
-
-      if (C.IsNull()) continue;
-
-      for (expV.Initialize(E.Oriented(TopAbs_FORWARD)); 
-           expV.More(); expV.Next()) {
-        
-        const TopoDS_Vertex& V = TopoDS::Vertex(expV.Value());
-        
-        TopAbs_Orientation Vori = V.Orientation();
-        if ( Vori == TopAbs_INTERNAL ) {
-          continue;
-        }
-        
-        Standard_Real p = BRep_Tool::Parameter(V,E,F);
-        C->D0(p,P);
-        if (!theVertices.IsBound(V)) 
-          theVertices.Bind(V,emptySequence);
-        TColgp_SequenceOfPnt2d& S = theVertices(V);
-        for (i = 1; i <= S.Length(); i++) {
-          if (P.Distance(S(i)) < tolerance) break;
-        }
-        if (i > S.Length())
-          S.Append(P);
+      Handle(BRep_GCurve) GC = Handle(BRep_GCurve)::DownCast(itLCR.Value());
+      if (!GC.IsNull() && GC->IsCurveOnSurface(aSurf, aELoc))
+      {
+        // Update UV points
+        GC->Update();
+        break;
       }
     }
   }
-  // second edge loop, update the edges 2d points
-  TopoDS_Vertex Vf,Vl;
-  gp_Pnt2d Pf,Pl;
-
-  for(Standard_Integer j = 1; j <= aShSeq.Length(); j++)
-  {
-    const TopoDS_Edge& E = TopoDS::Edge(aShSeq.Value(j));
-    const Handle(Geom2d_Curve)& C = aCSeq.Value(j);
-    if (C.IsNull()) continue;
-    
-    TopExp::Vertices(E,Vf,Vl);
-    if (Vf.IsNull()) {
-      Pf.SetCoord(RealLast(),RealLast());
-    }
-    else {
-      if ( Vf.Orientation() == TopAbs_INTERNAL ) {
-        continue;
-      }
-      const TColgp_SequenceOfPnt2d& seqf = theVertices(Vf);
-      if (seqf.Length() == 1) 
-        Pf = seqf(1);
-      else {
-        C->D0(aFSeq.Value(j),Pf);
-        for (i = 1; i <= seqf.Length(); i++) {
-          if (Pf.Distance(seqf(i)) <= tolerance) {
-            Pf = seqf(i);
-            break;
-          }
-        }
-      }
-    }
-    if (Vl.IsNull()) {
-      Pl.SetCoord(RealLast(),RealLast());
-    }
-    else {
-      if ( Vl.Orientation() == TopAbs_INTERNAL ) {
-        continue;
-      }
-      const TColgp_SequenceOfPnt2d& seql = theVertices(Vl);
-      if (seql.Length() == 1) 
-        Pl = seql(1);
-      else {
-        C->D0(aLSeq.Value(j),Pl);
-        for (i = 1; i <= seql.Length(); i++) {
-          if (Pl.Distance(seql(i)) <= tolerance) {
-            Pl = seql(i);
-            break;
-          }
-        }
-      }
-    }
-
-    // set the correct points
-    BRep_Tool::SetUVPoints(E,F,Pf,Pl);
-  }
 }
 
-
-
 //=======================================================================
 //function : Compare
 //purpose  : 
@@ -554,22 +654,6 @@ TopoDS_Wire  BRepTools::OuterWire(const TopoDS_Face& F)
   return Wres;
 }
 
-
-//=======================================================================
-//function : OuterShell
-//purpose  : 
-//=======================================================================
-
-TopoDS_Shell  BRepTools::OuterShell(const TopoDS_Solid& S)
-{
-  TopExp_Explorer its(S,TopAbs_SHELL);
-  if (its.More())
-    return TopoDS::Shell(its.Current());
-  else
-    return TopoDS_Shell();
-}
-
-
 //=======================================================================
 //function : Map3DEdges
 //purpose  : 
@@ -598,18 +682,6 @@ void  BRepTools::Dump(const TopoDS_Shape& Sh, Standard_OStream& S)
   SS.Dump(S);
 }
 
-#ifdef DEB
-//=======================================================================
-//function : BRepTools_Write 
-//purpose  : 
-//=======================================================================
-void BRepTools_Write (const TopoDS_Shape& S,
-                      const Standard_CString File)
-{
-  BRepTools::Write (S,File);  
-}
-#endif
-
 //=======================================================================
 //function : Write
 //purpose  : 
@@ -652,9 +724,9 @@ Standard_Boolean  BRepTools::Write(const TopoDS_Shape& Sh,
                                    const Handle(Message_ProgressIndicator)& PR)
 {
   ofstream os;
-  //  if (!fic.open(File,output)) return Standard_False;
-  os.open(File, ios::out);
-  if (!os.rdbuf()->is_open()) return Standard_False;
+  OSD_OpenStream(os, File, ios::out);
+  if (!os.is_open() || !os.good())
+    return Standard_False;
 
   Standard_Boolean isGood = (os.good() && !os.eof());
   if(!isGood)
@@ -691,8 +763,9 @@ Standard_Boolean BRepTools::Read(TopoDS_Shape& Sh,
 {
   filebuf fic;
   istream in(&fic);
-  if (!fic.open(File, ios::in)) return Standard_False;
-
+  OSD_OpenStream (fic, File, ios::in);
+  if(!fic.is_open()) return Standard_False;
+  
   BRepTools_ShapeSet SS(B);
   SS.SetProgress(PR);
   SS.Read(in);
@@ -707,47 +780,106 @@ Standard_Boolean BRepTools::Read(TopoDS_Shape& Sh,
 //purpose  : 
 //=======================================================================
 
-void BRepTools::Clean(const TopoDS_Shape& S)
+void BRepTools::Clean(const TopoDS_Shape& theShape)
 {
-  BRep_Builder B;
-  TopExp_Explorer ex;
-  Handle(Poly_Triangulation) TNULL, T;
-  Handle(Poly_PolygonOnTriangulation) PolyNULL, Poly;
+  BRep_Builder aBuilder;
+  Handle(Poly_Triangulation) aNullTriangulation;
+  Handle(Poly_PolygonOnTriangulation) aNullPoly;
 
-  if (!S.IsNull()) {
-    TopLoc_Location L;
-    for (ex.Init(S,TopAbs_FACE);ex.More();ex.Next()) {
-      const TopoDS_Face& F = TopoDS::Face(ex.Current());
-      B.UpdateFace(F, TNULL);
-    }
-    for (ex.Init(S, TopAbs_EDGE); ex.More(); ex.Next()) {
-      const TopoDS_Edge& E = TopoDS::Edge(ex.Current());
-// agv 21.09.01 : Inefficient management of Locations -> improve performance
-//    do {
-//      BRep_Tool::PolygonOnTriangulation(E, Poly, T, L);
-//      B.UpdateEdge(E, PolyNULL, T, L);
-//    } while(!Poly.IsNull());
-//
-      Handle(BRep_CurveRepresentation) cr;
-      const Handle(BRep_TEdge)& TE = *((Handle(BRep_TEdge)*) &E.TShape());
-      BRep_ListOfCurveRepresentation& lcr = TE -> ChangeCurves();
-      BRep_ListIteratorOfListOfCurveRepresentation itcr(lcr);
-
-      // find and remove all representations
-      while (itcr.More()) {
-        cr = itcr.Value();
-        if (cr->IsPolygonOnTriangulation())
-          lcr.Remove(itcr);
-        else
-          itcr.Next();
-      }
-      TE->Modified(Standard_True);
-// agv : fin
+  if (theShape.IsNull())
+    return;
+
+  TopExp_Explorer aFaceIt(theShape, TopAbs_FACE);
+  for (; aFaceIt.More(); aFaceIt.Next())
+  {
+    const TopoDS_Face& aFace = TopoDS::Face(aFaceIt.Current());
+
+    TopLoc_Location aLoc;
+    const Handle(Poly_Triangulation)& aTriangulation =
+      BRep_Tool::Triangulation(aFace, aLoc);
+
+    if (aTriangulation.IsNull())
+      continue;
+
+    // Nullify edges
+    TopExp_Explorer aEdgeIt(aFace, TopAbs_EDGE);
+    for (; aEdgeIt.More(); aEdgeIt.Next())
+    {
+      const TopoDS_Edge& aEdge = TopoDS::Edge(aEdgeIt.Current());
+      aBuilder.UpdateEdge(aEdge, aNullPoly, aTriangulation, aLoc);
     }
+
+    aBuilder.UpdateFace(aFace, aNullTriangulation);
+  }
+
+  // Iterate over all edges seeking for 3d polygons
+  Handle (Poly_Polygon3D) aNullPoly3d;
+  TopExp_Explorer aEdgeIt (theShape, TopAbs_EDGE);
+  for (; aEdgeIt.More (); aEdgeIt.Next ())
+  {
+    const TopoDS_Edge& aEdge = TopoDS::Edge (aEdgeIt.Current ());
+
+    TopLoc_Location aLoc;
+    Handle (Poly_Polygon3D) aPoly3d = BRep_Tool::Polygon3D (aEdge, aLoc);
+    if (aPoly3d.IsNull ())
+      continue;
+
+    aBuilder.UpdateEdge (aEdge, aNullPoly3d);  
   }
 }
 
+//=======================================================================
+//function : RemoveUnusedPCurves
+//purpose  : 
+//=======================================================================
+
+void BRepTools::RemoveUnusedPCurves(const TopoDS_Shape& S)
+{
+  TColStd_MapOfTransient UsedSurfaces;
+  
+  TopExp_Explorer Explo(S, TopAbs_FACE);
+  for (; Explo.More(); Explo.Next())
+  {
+    TopoDS_Face aFace = TopoDS::Face(Explo.Current());
+    TopLoc_Location aLoc;
+    Handle(Geom_Surface) aSurf = BRep_Tool::Surface(aFace, aLoc);
+    UsedSurfaces.Add(aSurf);
+  }
 
+  TopTools_IndexedMapOfShape Emap;
+  TopExp::MapShapes(S, TopAbs_EDGE, Emap);
+
+  Standard_Integer i;
+  for (i = 1; i <= Emap.Extent(); i++)
+  {
+    const Handle(BRep_TEdge)& TE = *((Handle(BRep_TEdge)*) &Emap(i).TShape());
+    BRep_ListOfCurveRepresentation& lcr = TE -> ChangeCurves();
+    BRep_ListIteratorOfListOfCurveRepresentation itrep(lcr );
+    while (itrep.More())
+    {
+      Standard_Boolean ToRemove = Standard_False;
+      
+      Handle(BRep_CurveRepresentation) CurveRep = itrep.Value();
+      if (CurveRep->IsCurveOnSurface())
+      {
+        Handle(Geom_Surface) aSurface = CurveRep->Surface();
+        if (!UsedSurfaces.Contains(aSurface))
+          ToRemove = Standard_True;
+      }
+      else if (CurveRep->IsRegularity())
+      {
+        Handle(Geom_Surface) Surf1 = CurveRep->Surface();
+        Handle(Geom_Surface) Surf2 = CurveRep->Surface2();
+        ToRemove = (!UsedSurfaces.Contains(Surf1) || !UsedSurfaces.Contains(Surf2));
+      }
+      
+      if (ToRemove)
+        lcr.Remove(itrep);
+      else
+        itrep.Next();
+    }
+  }
+}
 
 //=======================================================================
 //function : Triangulation
@@ -798,5 +930,129 @@ Standard_Boolean BRepTools::IsReallyClosed(const TopoDS_Edge& E,
   return nbocc == 2;
 }
 
+//=======================================================================
+//function : DetectClosedness
+//purpose  : 
+//=======================================================================
+
+void BRepTools::DetectClosedness(const TopoDS_Face& theFace,
+                                 Standard_Boolean&  theUclosed,
+                                 Standard_Boolean&  theVclosed)
+{
+  theUclosed = theVclosed = Standard_False;
+  
+  BRepAdaptor_Surface BAsurf(theFace, Standard_False);
+  Standard_Boolean IsSurfUclosed = BAsurf.IsUClosed();
+  Standard_Boolean IsSurfVclosed = BAsurf.IsVClosed();
+  if (!IsSurfUclosed && !IsSurfVclosed)
+    return;
+  
+  TopExp_Explorer Explo(theFace, TopAbs_EDGE);
+  for (; Explo.More(); Explo.Next())
+  {
+    const TopoDS_Edge& anEdge = TopoDS::Edge(Explo.Current());
+    if (BRepTools::IsReallyClosed(anEdge, theFace))
+    {
+      Standard_Real fpar, lpar;
+      Handle(Geom2d_Curve) aPCurve = BRep_Tool::CurveOnSurface(anEdge, theFace, fpar, lpar);
+      Standard_Boolean IsUiso = IsPCurveUiso(aPCurve, fpar, lpar);
+      if (IsSurfUclosed && IsUiso)
+        theUclosed = Standard_True;
+      if (IsSurfVclosed && !IsUiso)
+        theVclosed = Standard_True;
+      
+      if (theUclosed && theVclosed)
+        break;
+    }
+  }
+}
+
+//=======================================================================
+//function : EvalAndUpdateTol
+//purpose  : 
+//=======================================================================
+
+Standard_Real BRepTools::EvalAndUpdateTol(const TopoDS_Edge& theE, 
+                                 const Handle(Geom_Curve)& C3d, 
+                                 const Handle(Geom2d_Curve) C2d, 
+                                 const Handle(Geom_Surface)& S,
+                                 const Standard_Real f,
+                                 const Standard_Real l)
+{
+  Standard_Real newtol = 0.;
+  Standard_Real first = f, last = l;
+  //Set first, last to avoid ErrosStatus = 2 because of 
+  //too strong checking of limits in class CheckCurveOnSurface
+  //
+  if(!C3d->IsPeriodic())
+  {
+    first = Max(first, C3d->FirstParameter());
+    last = Min(last, C3d->LastParameter());
+  }
+  if(!C2d->IsPeriodic())
+  {
+    first = Max(first, C2d->FirstParameter());
+    last = Min(last, C2d->LastParameter());
+  }
+
+  GeomLib_CheckCurveOnSurface CT(C3d, S, first, last);
+  CT.Perform(C2d);
+  if(CT.IsDone())
+  {
+    newtol = CT.MaxDistance();
+  }
+  else
+  {
+    if(CT.ErrorStatus() == 3 || (CT.ErrorStatus() == 2 &&
+      (C3d->IsPeriodic() || C2d->IsPeriodic())))
+    {
+      //Try to estimate by sample points
+      Standard_Integer nbint = 22;
+      Standard_Real dt = (last - first) / nbint;
+      dt = Max(dt, Precision::Confusion());
+      Standard_Real d, dmax = 0.;
+      gp_Pnt2d aP2d;
+      gp_Pnt aPC, aPS;
+      Standard_Integer cnt = 0; 
+      Standard_Real t = first;
+      for(; t <= last; t += dt)
+      {
+        cnt++;
+        C2d->D0(t, aP2d);
+        C3d->D0(t, aPC);
+        S->D0(aP2d.X(), aP2d.Y(), aPS);
+        d = aPS.SquareDistance(aPC);
+        if(d > dmax)
+        {
+          dmax = d;
+        }
+      }
+      if(cnt < nbint + 1)
+      {
+        t = last;
+        C2d->D0(t, aP2d);
+        C3d->D0(t, aPC);
+        S->D0(aP2d.X(), aP2d.Y(), aPS);
+        d = aPS.SquareDistance(aPC);
+        if(d > dmax)
+        {
+          dmax = d;
+        }
+      }
+
+      newtol = 1.2 * Sqrt(dmax);
+    }
+  }
+  Standard_Real Tol = BRep_Tool::Tolerance(theE);
+  if(newtol > Tol)
+  {
+    Tol = newtol;
+    BRep_Builder B;
+    B.UpdateEdge(theE, Tol);
+  }
+
+  return Tol;
+
+}