Path: blob/devel/ElmerGUI/netgen/libsrc/meshing/meshclass.hpp
3206 views
#ifndef MESHCLASS1#define MESHCLASS23/**************************************************************************/4/* File: meshclass.hpp */5/* Author: Joachim Schoeberl */6/* Date: 20. Nov. 99 */7/**************************************************************************/89/*10The mesh class11*/12131415enum resthtype { RESTRICTH_FACE, RESTRICTH_EDGE,16RESTRICTH_SURFACEELEMENT, RESTRICTH_POINT, RESTRICTH_SEGMENT };1718class HPRefElement;192021/// 2d/3d mesh22class Mesh23{24public:25typedef MoveableArray<MeshPoint,PointIndex::BASE> T_POINTS;26typedef MoveableArray<Element> T_VOLELEMENTS;27typedef MoveableArray<Element2d> T_SURFELEMENTS;2829// typedef ARRAY<MeshPoint,PointIndex::BASE> T_POINTS;30// typedef ARRAY<Element> T_VOLELEMENTS;31// typedef ARRAY<Element2d> T_SURFELEMENTS;323334private:35/// point coordinates36T_POINTS points;3738/// type of element, set in calcsurfacesofnode39// ARRAY<ELEMENTTYPE> eltyps;4041/// line-segments at edges42ARRAY<Segment> segments;43/// surface elements, 2d-inner elements44T_SURFELEMENTS surfelements;45/// volume elements46T_VOLELEMENTS volelements;47/// points will be fixed forever48ARRAY<PointIndex> lockedpoints;495051/// surface indices at boundary nodes52TABLE<int,PointIndex::BASE> surfacesonnode;53/// boundary edges (1..normal bedge, 2..segment)54INDEX_2_CLOSED_HASHTABLE<int> * boundaryedges;55///56INDEX_2_CLOSED_HASHTABLE<int> * segmentht;57///58INDEX_3_CLOSED_HASHTABLE<int> * surfelementht;5960/// faces of rest-solid61ARRAY<Element2d> openelements;62/// open segmenets for surface meshing63ARRAY<Segment> opensegments;64656667/**68Representation of local mesh-size h69*/70LocalH * lochfunc;71///72double hglob;73///74double hmin;75///76ARRAY<double> maxhdomain;7778/**79the face-index of the surface element maps into80this table.81*/82ARRAY<FaceDescriptor> facedecoding;8384/// sub-domain materials85ARRAY<char*> materials;8687ARRAY<string*, 0> bcnames;8889/// Periodic surface, close surface, etc. identifications90Identifications * ident;919293/// number of vertices (if < 0, use np)94int numvertices;9596/// geometric search tree for interval intersection search97Box3dTree * elementsearchtree;98/// time stamp for tree99int elementsearchtreets;100101/// element -> face, element -> edge etc ...102class MeshTopology * topology;103/// methods for high order elements104class CurvedElements * curvedelems;105106/// nodes identified by close points107class AnisotropicClusters * clusters;108109/// space dimension (2 or 3)110int dimension;111112/// changed by every minor modification (addpoint, ...)113int timestamp;114/// changed after finishing global algorithm (improve, ...)115int majortimestamp;116117/// mesh access semaphors.118NgMutex mutex;119/// mesh access semaphors.120NgMutex majormutex;121122SYMBOLTABLE< ARRAY<int>* > userdata_int;123SYMBOLTABLE< ARRAY<double>* > userdata_double;124125126mutable ARRAY< Point3d > pointcurves;127mutable ARRAY<int> pointcurves_startpoint;128mutable ARRAY<double> pointcurves_red,pointcurves_green,pointcurves_blue;129130131/// start element for point search (GetElementOfPoint)132mutable int ps_startelement;133134135#ifdef PARALLEL136/// connection to parallel meshes137class ParallelMeshTopology * paralleltop;138139#endif140141142private:143void BuildBoundaryEdges(void);144145public:146bool PointContainedIn2DElement(const Point3d & p,147double lami[3],148const int element,149bool consider3D = false) const;150bool PointContainedIn3DElement(const Point3d & p,151double lami[3],152const int element) const;153bool PointContainedIn3DElementOld(const Point3d & p,154double lami[3],155const int element) const;156157public:158159// store coarse mesh before hp-refinement160ARRAY<HPRefElement> * hpelements;161Mesh * coarsemesh;162163164/// number of refinement levels165int mglevels;166/// refinement hierarchy167ARRAY<INDEX_2,PointIndex::BASE> mlbetweennodes;168/// parent element of volume element169ARRAY<int> mlparentelement;170/// parent element of surface element171ARRAY<int> mlparentsurfaceelement;172173174175///176Mesh();177///178~Mesh();179180Mesh & operator= (const Mesh & mesh2);181182///183void DeleteMesh();184185///186void ClearSurfaceElements()187{188surfelements.SetSize(0);189timestamp = NextTimeStamp();190}191192///193void ClearVolumeElements()194{195volelements.SetSize(0);196// eltyps.SetSize(0);197timestamp = NextTimeStamp();198}199200///201void ClearSegments()202{203segments.SetSize(0);204timestamp = NextTimeStamp();205}206207///208bool TestOk () const;209210void SetAllocSize(int nnodes, int nsegs, int nsel, int nel);211212213PointIndex AddPoint (const Point3d & p, int layer = 1);214PointIndex AddPoint (const Point3d & p, int layer, POINTTYPE type);215#ifdef PARALLEL216PointIndex AddPoint (const Point3d & p, bool aisghost, int layer = 1);217PointIndex AddPoint (const Point3d & p, bool aisghost, int layer, POINTTYPE type);218#endif219int GetNP () const { return points.Size(); }220221MeshPoint & Point(int i) { return points.Elem(i); }222MeshPoint & Point(PointIndex pi) { return points[pi]; }223const MeshPoint & Point(int i) const { return points.Get(i); }224const MeshPoint & Point(PointIndex pi) const { return points[pi]; }225226const MeshPoint & operator[] (PointIndex pi) const { return points[pi]; }227MeshPoint & operator[] (PointIndex pi) { return points[pi]; }228229const T_POINTS & Points() const { return points; }230T_POINTS & Points() { return points; }231232233SegmentIndex AddSegment (const Segment & s);234void DeleteSegment (int segnr)235{236segments.Elem(segnr).p1 = PointIndex::BASE-1;237segments.Elem(segnr).p2 = PointIndex::BASE-1;238}239void FullDeleteSegment (int segnr)240{241segments.Delete(segnr-PointIndex::BASE);242}243244int GetNSeg () const { return segments.Size(); }245Segment & LineSegment(int i) { return segments.Elem(i); }246const Segment & LineSegment(int i) const { return segments.Get(i); }247248Segment & LineSegment(SegmentIndex si) { return segments[si]; }249const Segment & LineSegment(SegmentIndex si) const { return segments[si]; }250const Segment & operator[] (SegmentIndex si) const { return segments[si]; }251Segment & operator[] (SegmentIndex si) { return segments[si]; }252253254255256SurfaceElementIndex AddSurfaceElement (const Element2d & el);257void DeleteSurfaceElement (int eli)258{259surfelements.Elem(eli).Delete();260surfelements.Elem(eli).PNum(1) = -1;261surfelements.Elem(eli).PNum(2) = -1;262surfelements.Elem(eli).PNum(3) = -1;263timestamp = NextTimeStamp();264}265266void DeleteSurfaceElement (SurfaceElementIndex eli)267{268DeleteSurfaceElement (int(eli)+1);269}270271int GetNSE () const { return surfelements.Size(); }272Element2d & SurfaceElement(int i) { return surfelements.Elem(i); }273const Element2d & SurfaceElement(int i) const { return surfelements.Get(i); }274275Element2d & SurfaceElement(SurfaceElementIndex i)276{ return surfelements[i]; }277const Element2d & SurfaceElement(SurfaceElementIndex i) const278{ return surfelements[i]; }279280const Element2d & operator[] (SurfaceElementIndex ei) const281{ return surfelements[ei]; }282Element2d & operator[] (SurfaceElementIndex ei)283{ return surfelements[ei]; }284285286void GetSurfaceElementsOfFace (int facenr, ARRAY<SurfaceElementIndex> & sei) const;287288ElementIndex AddVolumeElement (const Element & el);289290int GetNE () const { return volelements.Size(); }291292Element & VolumeElement(int i) { return volelements.Elem(i); }293const Element & VolumeElement(int i) const { return volelements.Get(i); }294Element & VolumeElement(ElementIndex i) { return volelements[i]; }295const Element & VolumeElement(ElementIndex i) const { return volelements[i]; }296297const Element & operator[] (ElementIndex ei) const298{ return volelements[ei]; }299Element & operator[] (ElementIndex ei)300{ return volelements[ei]; }301302303304305// ELEMENTTYPE ElementType (int i) const { return eltyps.Get(i); }306307308// ELEMENTTYPE ElementType (int i) const309// { return (volelements.Get(i).fixed) ? FIXEDELEMENT : FREEELEMENT; }310311ELEMENTTYPE ElementType (ElementIndex i) const312{ return (volelements[i].flags.fixed) ? FIXEDELEMENT : FREEELEMENT; }313314/*315ELEMENTTYPE ElementType (int i) const { return eltyps.Get(i); }316ELEMENTTYPE ElementType (ElementIndex i) const { return eltyps[i]; }317*/318319const T_VOLELEMENTS & VolumeElements() const { return volelements; }320T_VOLELEMENTS & VolumeElements() { return volelements; }321322323///324double ElementError (int eli) const;325326///327void AddLockedPoint (PointIndex pi);328///329void ClearLockedPoints ();330331const ARRAY<PointIndex> & LockedPoints() const332{ return lockedpoints; }333334/// Returns number of domains335int GetNDomains() const;336337338///339int GetDimension() const340{ return dimension; }341void SetDimension(int dim)342{ dimension = dim; }343344/// sets internal tables345void CalcSurfacesOfNode ();346347/// additional (temporarily) fix points348void FixPoints (const BitArray & fixpoints);349350/**351finds elements without neighbour and352boundary elements without inner element.353Results are stored in openelements.354if dom == 0, all sub-domains, else subdomain dom */355void FindOpenElements (int dom = 0);356357358/**359finds segments without surface element,360and surface elements without neighbours.361store in opensegmentsy362*/363void FindOpenSegments (int surfnr = 0);364/**365remove one layer of surface elements366*/367void RemoveOneLayerSurfaceElements ();368369370int GetNOpenSegments () { return opensegments.Size(); }371const Segment & GetOpenSegment (int nr) { return opensegments.Get(nr); }372373/**374Checks overlap of boundary375return == 1, iff overlap376*/377int CheckOverlappingBoundary ();378/**379Checks consistent boundary380return == 0, everything ok381*/382int CheckConsistentBoundary () const;383384/*385checks element orientation386*/387int CheckVolumeMesh () const;388389390/**391finds average h of surface surfnr if surfnr > 0,392else of all surfaces.393*/394double AverageH (int surfnr = 0) const;395/// Calculates localh396void CalcLocalH ();397///398void SetLocalH (const Point3d & pmin, const Point3d & pmax, double grading);399///400void RestrictLocalH (const Point3d & p, double hloc);401///402void RestrictLocalHLine (const Point3d & p1, const Point3d & p2,403double hloc);404/// number of elements per radius405void CalcLocalHFromSurfaceCurvature(double elperr);406///407void CalcLocalHFromPointDistances(void);408///409void RestrictLocalH (resthtype rht, int nr, double loch);410///411void LoadLocalMeshSize (const char * meshsizefilename);412///413void SetGlobalH (double h);414///415void SetMinimalH (double h);416///417double MaxHDomain (int dom) const;418///419void SetMaxHDomain (const ARRAY<double> & mhd);420///421double GetH (const Point3d & p) const;422///423double GetMinH (const Point3d & pmin, const Point3d & pmax);424///425LocalH & LocalHFunction () { return * lochfunc; }426///427bool LocalHFunctionGenerated(void) const { return (lochfunc != NULL); }428429/// Find bounding box430void GetBox (Point3d & pmin, Point3d & pmax, int dom = -1) const;431432/// Find bounding box of points of typ ptyp or less433void GetBox (Point3d & pmin, Point3d & pmax, POINTTYPE ptyp ) const;434435///436int GetNOpenElements() const437{ return openelements.Size(); }438///439const Element2d & OpenElement(int i) const440{ return openelements.Get(i); }441442443/// are also quads open elements444bool HasOpenQuads () const;445446/// split into connected pieces447void SplitIntoParts ();448449///450void SplitSeparatedFaces ();451452/// Refines mesh and projects points to true surface453// void Refine (int levels, const CSGeometry * geom);454455456bool BoundaryEdge (PointIndex pi1, PointIndex pi2) const457{458if(!boundaryedges)459const_cast<Mesh *>(this)->BuildBoundaryEdges();460461INDEX_2 i2 (pi1, pi2);462i2.Sort();463return boundaryedges->Used (i2);464}465466bool IsSegment (PointIndex pi1, PointIndex pi2) const467{468INDEX_2 i2 (pi1, pi2);469i2.Sort();470return segmentht->Used (i2);471}472473SegmentIndex SegmentNr (PointIndex pi1, PointIndex pi2) const474{475INDEX_2 i2 (pi1, pi2);476i2.Sort();477return segmentht->Get (i2);478}479480481/**482Remove unused points. etc.483*/484void Compress ();485486///487void Save (ostream & outfile) const;488///489void Load (istream & infile);490///491void Merge (istream & infile, const int surfindex_offset = 0);492///493void Save (const string & filename) const;494///495void Load (const string & filename);496///497void Merge (const string & filename, const int surfindex_offset = 0);498499500///501void ImproveMesh (OPTIMIZEGOAL goal = OPT_QUALITY);502503///504void ImproveMeshJacobian (OPTIMIZEGOAL goal = OPT_QUALITY, const BitArray * usepoint = NULL);505///506void ImproveMeshJacobianOnSurface (const BitArray & usepoint,507const ARRAY< Vec<3>* > & nv,508OPTIMIZEGOAL goal = OPT_QUALITY,509const ARRAY< ARRAY<int,PointIndex::BASE>* > * idmaps = NULL);510/*511#ifdef SOLIDGEOM512/// old513void ImproveMesh (const CSGeometry & surfaces,514OPTIMIZEGOAL goal = OPT_QUALITY);515#endif516*/517518/**519free nodes in environment of openelements520for optimiztion521*/522void FreeOpenElementsEnvironment (int layers);523524///525bool LegalTet (Element & el) const526{527if (el.IllegalValid())528return !el.Illegal();529return LegalTet2 (el);530}531///532bool LegalTet2 (Element & el) const;533534535///536bool LegalTrig (const Element2d & el) const;537/**538if values non-null, return values in 4-double array:539triangle angles min/max, tetangles min/max540if null, output results on cout541*/542void CalcMinMaxAngle (double badellimit, double * retvalues = NULL);543544/*545Marks elements which are dangerous to refine546return: number of illegal elements547*/548int MarkIllegalElements ();549550/// orient surface mesh, for one sub-domain only551void SurfaceMeshOrientation ();552553/// convert mixed element mesh to tet-mesh554void Split2Tets();555556557/// build box-search tree558void BuildElementSearchTree ();559560void SetPointSearchStartElement(const int el) const {ps_startelement = el;}561562/// gives element of point, barycentric coordinates563int GetElementOfPoint (const Point3d & p,564double * lami,565bool build_searchtree = 0,566const int index = -1,567const bool allowindex = true) const;568int GetElementOfPoint (const Point3d & p,569double * lami,570const ARRAY<int> * const indices,571bool build_searchtree = 0,572const bool allowindex = true) const;573int GetSurfaceElementOfPoint (const Point3d & p,574double * lami,575bool build_searchtree = 0,576const int index = -1,577const bool allowindex = true) const;578int GetSurfaceElementOfPoint (const Point3d & p,579double * lami,580const ARRAY<int> * const indices,581bool build_searchtree = 0,582const bool allowindex = true) const;583584/// give list of vol elements which are int the box(p1,p2)585void GetIntersectingVolEls(const Point3d& p1, const Point3d& p2,586ARRAY<int> & locels) const;587588///589int AddFaceDescriptor(const FaceDescriptor& fd)590{ return facedecoding.Append(fd); }591592593///594void SetMaterial (int domnr, const char * mat);595///596const char * GetMaterial (int domnr) const;597598void SetNBCNames ( int nbcn );599600void SetBCName ( int bcnr, const string & abcname );601602string GetBCName ( int bcnr ) const;603604string * GetBCNamePtr ( int bcnr )605{ return bcnames[bcnr]; }606607///608void ClearFaceDescriptors()609{ facedecoding.SetSize(0); }610611///612int GetNFD () const613{ return facedecoding.Size(); }614615const FaceDescriptor & GetFaceDescriptor (int i) const616{ return facedecoding.Get(i); }617618///619FaceDescriptor & GetFaceDescriptor (int i)620{ return facedecoding.Elem(i); }621622// #ifdef NONE623// /*624// Identify points pi1 and pi2, due to625// identification nr identnr626// */627// void AddIdentification (int pi1, int pi2, int identnr);628629// int GetIdentification (int pi1, int pi2) const;630// int GetIdentificationSym (int pi1, int pi2) const;631// ///632// INDEX_2_HASHTABLE<int> & GetIdentifiedPoints ()633// {634// return *identifiedpoints;635// }636637// ///638// void GetIdentificationMap (int identnr, ARRAY<int> & identmap) const;639// ///640// void GetIdentificationPairs (int identnr, ARRAY<INDEX_2> & identpairs) const;641// ///642// int GetMaxIdentificationNr () const643// {644// return maxidentnr;645// }646// #endif647648/// return periodic, close surface etc. identifications649Identifications & GetIdentifications () { return *ident; }650/// return periodic, close surface etc. identifications651const Identifications & GetIdentifications () const { return *ident; }652653654void InitPointCurve(double red = 1, double green = 0, double blue = 0) const;655void AddPointCurvePoint(const Point3d & pt) const;656int GetNumPointCurves(void) const;657int GetNumPointsOfPointCurve(int curve) const;658Point3d & GetPointCurvePoint(int curve, int n) const;659void GetPointCurveColor(int curve, double & red, double & green, double & blue) const;660661662663664/// find number of vertices665void ComputeNVertices ();666/// number of vertices (no edge-midpoints)667int GetNV () const;668/// remove edge points669void SetNP (int np);670671672673674/*675/// build connected nodes along prism stack676void BuildConnectedNodes ();677void ConnectToNodeRec (int node, int tonode,678const TABLE<int> & conto);679*/680681bool PureTrigMesh (int faceindex = 0) const;682bool PureTetMesh () const;683684685const class MeshTopology & GetTopology () const686{ return *topology; }687688void UpdateTopology();689690class CurvedElements & GetCurvedElements () const691{ return *curvedelems; }692693const class AnisotropicClusters & GetClusters () const694{ return *clusters; }695696int GetTimeStamp() const { return timestamp; }697void SetNextTimeStamp()698{ timestamp = NextTimeStamp(); }699700int GetMajorTimeStamp() const { return majortimestamp; }701void SetNextMajorTimeStamp()702{ majortimestamp = timestamp = NextTimeStamp(); }703704705/// return mutex706NgMutex & Mutex () { return mutex; }707NgMutex & MajorMutex () { return majormutex; }708709710///711void SetUserData(const char * id, ARRAY<int> & data);712///713bool GetUserData(const char * id, ARRAY<int> & data, int shift = 0) const;714///715void SetUserData(const char * id, ARRAY<double> & data);716///717bool GetUserData(const char * id, ARRAY<double> & data, int shift = 0) const;718719///720friend void OptimizeRestart (Mesh & mesh3d);721///722void PrintMemInfo (ostream & ost) const;723///724friend class Meshing3;725726727enum GEOM_TYPE { NO_GEOM = 0, GEOM_2D = 1, GEOM_CSG = 10, GEOM_STL = 11, GEOM_OCC = 12, GEOM_ACIS = 13 };728GEOM_TYPE geomtype;729730731732#ifdef PARALLEL733/// returns parallel topology734class ParallelMeshTopology & GetParallelTopology () const735{ return *paralleltop; }736737738/// distributes the master-mesh to local meshes739void Distribute ();740741/// loads a mesh sent from master processor742void ReceiveParallelMesh ();743744/// find connection to parallel meshes745// void FindExchangePoints () ;746747// void FindExchangeEdges ();748// void FindExchangeFaces ();749750/// use metis to decompose master mesh751void ParallelMetis (); // ARRAY<int> & neloc );752void PartHybridMesh (); // ARRAY<int> & neloc );753void PartDualHybridMesh (); // ARRAY<int> & neloc );754void PartDualHybridMesh2D (); // ( ARRAY<int> & neloc );755756/// send mesh to parallel machine, keep global mesh at master757void SendMesh ( ) const; // Mesh * mastermesh, ARRAY<int> & neloc) const;758759void UpdateOverlap ();760761#endif762763764};765766inline ostream& operator<<(ostream& ost, const Mesh& mesh)767{768ost << "mesh: " << endl;769mesh.Save(ost);770return ost;771}772773774#endif775776777778779