dataStructure.h
Go to the documentation of this file.
00001 #ifndef _DATASTRUCTURE_H
00002 #define _DATASTRUCTURE_H
00003 #include "icMatrix.h"
00004 #include "icVector.h"
00005 typedef struct RegularElem{
00006         int ID;
00007         double base[2];                //base under global frame
00008         icVector2 Direct;                  //direction in global frame
00009         int type;                       //singular type (0 –regular, 1—convergent, 2—divergent)
00010         icMatrix3x3  transform_matrix;  //transformation matrix for user editing
00011         icMatrix3x3 transposeRot;   
00012         //visual control icons (control points)
00013         //double rate of decreasing (optional) ---not consider at this moment
00014 
00015         int basis_triangle;            //the triangle that contains the basis
00016 
00018         double rotang;
00019         double s;
00020 } RegularElement;
00021 
00022 typedef struct Point
00023 {
00024         double x, y;
00025         int cellid;
00026 }Point;
00027 
00028 
00029 
00030 typedef struct Singularities{
00031         double gcx, gcy;                 //global center
00032         float alpha[3];                  //the barycentric coordinates of the fixed point inside the triangle
00033         int Triangle_ID;                 //which triangle it belongs to
00034         double local_coordinates[3];     //we can choose to use 2D local coordinates or barycentric coordinates 
00035         int type;                        //singular type (0-–Null, 1—source, 2—sink, 3—saddle, 4—cwcenter, 
00036         //5—ccwcenter, 6—repel center, 7—attractive center )
00037         icMatrix3x3 Jacobian;            //local Jacobian matrix for this singularity
00038         icVector2 incoming, outgoing;    //for separatrices calculation beginning from a saddle
00039         //visual icons ( we need not store it, the display routine will use different colors to mark different kinds of singularities)
00040 
00041         /*---------Variables for Conley relation graph 10/14/05---------------*/
00042         int node_index;                  //the index of the node associates with this singularity
00043         int separtices;                  //the index of the separatrix group belongs to the saddle 10/13/05
00044         int selectedtraj;                //the index of selected separatrix for modification 12/23/05
00045         int *connected_limitcycles;      //An array of limit cycles that the saddle can reach
00046         int num_connected_limitcycles;   //number of the limit cycles inside the array 'connected_limitcycles'
00047 
00048         int connected;                   //1--connected with other element(s) 08/06/06
00049 } Singularities;
00050 
00051 
00052 typedef struct SampleListInTriangle{
00053         int which_traj;
00054         int limitcycle;
00055         int which_sample;
00056 }SampleListInTriangle;
00057 
00058 
00059 typedef struct QuadEdge{
00060         int index;                //Id for specific edge
00061         int verts[2];             //The two points for specific edge
00062         int tris[2];              //Two neighbor faces that share this edge
00063         bool visited;              //for my subdivision of the triangle mesh
00064         //double length;            //store the length of the edge
00065 
00066         /*---------Variables for pair cancellation---------------*/
00067         bool OnRepellBoundary;     //If the edge is at the boundary of repell region mark it as 1, otherwise 0 1/23/06
00068         bool OnAttractBoundary;    //If the edge is at the boundary of repell region mark it as 1, otherwise 0 1/23/06
00069         bool repell_visited;       //whether the edge has been visited during the boundary building
00070         bool attract_visited;
00071         icVector2 repell_normal;  //outward normal of the repeller region at the edge 
00072         icVector2 attract_normal; //outward normal of the attractor region at the edge 
00073 
00074         //icVector2 normal;
00075 
00077         bool OnBoundary;
00078         bool BoundaryVisited;
00079 
00080         /***---- For finding the separation and attachment points ----***/
00081         icMatrix2x2 Jacobian;     //for calculate the decomposition of the Jacobian
00082 
00084         icVector2 intersections[2];  //we store only the recent two intersections
00085         int num_intersections;
00086         //double pre_length;
00087 
00088         QuadEdge *next;
00089 }QuadEdge;
00090 
00091 typedef struct LinesInOneCell{
00092         int whichtraj;    /*the index of the tensor line*/
00093         int start, end;  /*from the "start" line segement to the "end" one*/
00094 }LinesInOneCell;
00095 class LineInfo{
00096 public:
00097         LinesInOneCell **lines;
00098         int nlines;
00099         int curMaxNum;
00100 
00101         LineInfo(int init_size = 0)
00102         {
00103                 if (init_size == 0)
00104                 {
00105                         lines = NULL;
00106                         nlines = curMaxNum = 0;
00107                         return;
00108                 }
00109 
00110                 lines = (LinesInOneCell**)malloc(sizeof(LinesInOneCell*)*init_size);
00111                 nlines = 0;
00112                 if(lines == NULL)
00113                         exit(-1);
00114                 curMaxNum = init_size;
00115                 for(int i=0; i<curMaxNum; i++)
00116                         lines[i]=NULL;
00117         }
00118 
00119         ~LineInfo()
00120         {
00121                 int i;
00122                 if(lines != NULL)
00123                 {
00124                         for(i=0; i<curMaxNum; i++)
00125                         {
00126                                 if(lines[i] != NULL)
00127                                         free(lines[i]);
00128                         }
00129 
00130                         free(lines);
00131                 }
00132         }
00133 
00134         void addNew(LinesInOneCell *l)
00135         {
00136                 if(nlines>=curMaxNum)
00137                 {
00138                         if(!extend(1))
00139                                 exit(-1);  /*probably not enough memory*/
00140                 }
00141                 lines[nlines] = l;
00142                 nlines++;
00143         }
00144 
00145         bool isFull()
00146         {
00147                 if(nlines>=curMaxNum)
00148                         return true;
00149                 return false;
00150         }
00151 
00152         bool extend(int step)
00153         {
00154                 LinesInOneCell **temp = lines;
00155                 lines = (LinesInOneCell**)malloc(sizeof(LinesInOneCell*)*(curMaxNum+step));
00156                 if(lines == NULL)
00157                         return false;
00158                 int i;
00159                 for(i=0; i<curMaxNum; i++)
00160                         lines[i]=temp[i];
00161                 for(i=curMaxNum; i<curMaxNum+step; i++)
00162                         lines[i]=NULL;
00163                 curMaxNum += step;
00164                 free(temp);
00165                 return true;
00166         }
00167 
00168         bool is_repeated(LinesInOneCell *l)
00169         {
00170                 int i;
00171                 for(i=0;i<nlines;i++)
00172                 {
00173                         if(l->whichtraj==lines[i]->whichtraj)
00174                                 return true;
00175                 }
00176                 return false;
00177         }
00178 };
00179 
00180 typedef struct QuadCell {
00181         unsigned char nverts;        // number of vertices in the list 
00182         int *verts;                  // indices of the vertices associated with current face list 
00183         int index;                  //index of current face
00184         void *other_props;           //other properties 
00185         //double area;                 //area of the face
00186         //icVector3 normal;           //normal of the face
00187         //icVector3 center;           //
00188 
00189         QuadEdge *edges[4];             //store the address of the associated edges
00190         int xstart, xend, ystart, yend;
00191         double x_start_coord, y_start_coord;
00192 
00193         /*---------Variables for pair cancellation---------------*/
00194         //bool repell_inregion;        //whether the triangle is inside the repeller neighborhood
00195         //bool attract_inregion;       //whether the triangle is inside the attractor neighborhood
00196 
00197         bool contain_degpt;    //flag to mark whether this triangle containing a singularity or not
00198         int degpt_index;      //id of the singularity contained by current triangle
00199 
00200         bool OnBoundary;
00201 
00202         /*----------For degenerate point detection (temp) ---------- 09/18/2007 */
00203         unsigned char degenerate_type;
00204 
00205         /*------------For streamline placement, using samplin point-----------*/ //copy at 07/22/06
00210 
00211         SampleListInTriangle *maj_samplepts, *min_samplepts;
00212         int maj_nsamplepts, min_nsamplepts;
00213         int MAJMaxSampNum, MINMaxSampNum;
00214 
00215         bool visited;
00216 
00217         /*----- For calculating the intersections and constructing the street net*/
00218         LineInfo *majorlines, *minorlines;
00219         bool hasmajor, hasminor;
00220 
00221         int *intersectlist;   /*a list of intersections in this cell*/
00222         unsigned char nintersects;      /*the number of the intersections in the list*/
00223 
00224         int *streetgraphedgelist;
00225         unsigned char nstreetgraphedges;
00226 
00227         /* for region division 11/22/2007*/
00228         LineInfo *sketchlines;
00229         unsigned char which_region;
00230 
00231         bool in_region;
00232         //bool in_veg;                  /*true -- in veg region;  false -- in regular land or water */
00233         bool is_contour_cell;
00234 
00235         /*  record the water boundaries that cross this cell  */
00236         int *mapbounds;
00237         int nmapbounds;
00238 
00239 } QuadCell;
00240 
00241 typedef struct TenRegularElem{
00242         int ID;
00243         double base[2], end[2];                //base under global frame
00244         icVector2 Direct;                  //direction in global frame
00245         unsigned char type;                       //singular type (0 –regular, 1—convergent, 2—divergent)
00246         icMatrix3x3  transform_matrix;  //transformation matrix for user editing
00247         icMatrix3x3  transpose_matrix;
00248 
00249         //icMatrix3x3 transposeRot;   
00250         //visual control icons (control points)
00251         //double rate of decreasing (optional) ---not consider at this moment
00252 
00253         int basis_triangle;            //the triangle that contains the basis
00254 
00256         //double originalang;
00257         double rotang;
00258         double s;
00259 
00260         bool deleted;
00261 
00263         unsigned char which_region;    //for two level tensor field design 11/17/2007
00264 }TenRegularElem;
00265 
00266 typedef struct QuadVertex {
00267         double x,y/*,z*/;             //the coordinates of the vertex under global frame
00268         double vx,vy/*,vz*/;
00269         double prob_on_path;
00270         void *other_props;        //other properties 
00271         //icVector3 normal;         //normal at the vertex
00272 
00273         int *edges_id;            //edges incident to current vertex
00274         unsigned char Num_edge;             //number of edges
00275         QuadEdge **edges;             //store the addresses of the edges incident to the vertex
00276 
00277     unsigned char ncells;     //number of cells that share this vertex
00278         QuadCell **cells;         //the cells that share this vertex
00279         
00280         /*---------Variables for region smoothing---------------*/
00281         bool OnBoundary; 
00282         bool InRegion;
00283         int index;               //*Index in the whole object vertices list
00284         int RegionListID;         //Index in the inner vertices list
00285         
00286         /*---------Variables for pair cancellation---------------*/
00287         //unsigned char repell_flag;          //for repeller neighborhood | 0--unknown, 1--on boundary, 2-- in region
00288         //unsigned char attract_flag;         //for attractor neighborhood | 0--unknown, 1--on boundary, 2-- in region
00289 
00291         int which_line;
00292         double distance;  /*for distance level set as well*/
00293         bool visited;
00294         unsigned char type;      /*0--far away; 1--in narrow band; 2--known 09/30/2007*/
00295 
00296         icMatrix2x2 Jacobian;    /*we will calculate it according to the Jacobian around its one ring neighbor*/
00297         icMatrix2x2 origin_ten;  /*the old Jacobian*/
00298         /*eigen vectors*/
00299         icVector2 major, minor;  /*for visualization only*/
00300         double major_ang, minor_ang;
00301         double tensor_major_ang;
00302         bool major_cos, major_sin, minor_cos, minor_sin;
00303         icVector2 tran_vec;      /*transfer eigen vector to a real vector field*/
00304 
00305         bool inland;             /*true -- in land; false -- in the water region*/
00306         bool inveg;              /*true -- in veg region;  false -- in regular land or water */
00307 
00308         unsigned char which_region;  /*for two level design 11/17/2007*/
00309         bool inbrushregion;
00310 
00311         /*   for multi-density tensor line placement   */
00312         double density;
00313 
00314         /*   for the asymmetric tensor field design 12/29/2007  */
00315         double phi;
00316 
00317 } QuadVertex;
00318 
00319 
00320 typedef struct EditBox{
00321         icVector2 p1, p2, p3, p4, Up;  
00322 }EditBox;
00323 
00324 typedef struct SingularElem{
00325         int ID;
00326         int Triangle_ID;                //the triangle that contains the singular element
00327         double centerx, centery;        //center under global frame
00328         int type;                       //singular type (0 –Null, 1—source, 2—sink, 3—saddle, 4—cwcenter, 
00329         //5—ccwcenter
00330         icMatrix3x3  transform_matrix;  //transformation matrix for user editing
00331         icMatrix3x3  Jacobian;
00332         //visual control icons ( edit box, control points)
00333         EditBox editbox;
00334         EditBox cur_editbox;
00335         //double rate of decreasing (optional) ---not consider at this moment
00336 
00338         double rotang;
00339         double sx, sy;
00340         double s;
00341         bool deleted;
00342 } SingularElement;
00343 
00344 typedef struct DegeneratePt{
00345         int degpt_index;
00346         double gcx, gcy;                 //global center
00347         float alpha[3];                  //the barycentric coordinates of the fixed point inside the triangle
00348         int Triangle_ID;                 //which triangle it belongs to
00349         double local_coordinates[3];     //we can choose to use 2D local coordinates or barycentric coordinates 
00350         int type;                        //degenerate type (0—wedge, 1—trisector, 2—node, 3—center, 
00351         //4—saddle, 5—other higher order)
00352         icMatrix2x2 ten;                 //local tensor for this degenerate point
00353         double s1_ang, s2_ang, s3_ang;   //the starting angles of the separatrices
00354         icVector2 s[3];
00355     icVector2 s_vec[3];
00356     bool s_ifLink[3];
00357     int nseps;             //the number of separatrices
00358     int nlinks;
00359     int links_index[3];
00360     int valid_index;
00361         //icVector2 s1, s2, s3;    //for separatrices calculation beginning from a saddle
00362         //visual icons ( we need not store it, the display routine will use different colors to mark different kinds of singularities)
00363 
00364         bool deleted;
00365 } DegeneratePt;
00366 
00367 typedef struct ScalarSingularElem{
00368         int index;
00369         double pos[2];
00370         unsigned char type;
00371         bool deleted;
00372 
00373         /*  for editing  */
00374 }ScalarSingularElem;
00375 
00376 typedef struct Degenerate_Design{
00377         int ID;
00378         int Triangle_ID;                //the triangle that contains the singular element
00379         double centerx, centery;        //center under global frame
00380         int type;                       //0 ?wedge, 1—trisector, 2—node, 3—center, 4—saddle, 
00381         //5—ccwcenter
00382         icMatrix3x3  transform_matrix;  //transformation matrix for user editing
00383         //icMatrix3x3  Jacobian;
00384         /*visual control icons ( edit box, control points)*/
00385         EditBox editbox;
00386         EditBox cur_editbox;
00387         //double rate of decreasing (optional) ---not consider at this moment
00388 
00390         double rotang;
00391         double sx, sy;
00392         double s;
00393         bool deleted;
00394 
00396         unsigned char which_region;    //for two level tensor field design 11/17/2007
00397 }Degenerate_Design;
00398 
00399 typedef struct Edge{
00400         int index;                //Id for specific edge
00401         int verts[2];             //The two points for specific edge
00402         int OppVerts[2];          //The two vertices that opposite to the edge
00403         int tris[2];              //Two neighbor faces that share this edge
00404         int visited;              //for my subdivision of the triangle mesh
00405         int MidPointID;           //The ID of the vertex of the middle point on the edge
00406         double length;            //store the length of the edge
00407 
00408         /*---------Variables for pair cancellation---------------*/
00409         int OnRepellBoundary;     //If the edge is at the boundary of repell region mark it as 1, otherwise 0 1/23/06
00410         int OnAttractBoundary;    //If the edge is at the boundary of repell region mark it as 1, otherwise 0 1/23/06
00411         int repell_visited;       //whether the edge has been visited during the boundary building
00412         int attract_visited;
00413         icVector2 repell_normal;  //outward normal of the repeller region at the edge 
00414         icVector2 attract_normal; //outward normal of the attractor region at the edge 
00415 
00416         icVector2 normal;
00417 
00419         int OnBoundary;
00420         int BoundaryVisited;
00421 
00422         /*----- To store the special points on the edge (two at most) 07/17/06 ----*/
00423         icVector2 attp, sep;
00424         int find_attp, find_sep;
00425         int att_visit, sep_visit;    //0 -- alive; 1--visited/dead;  2--too close/pending  07/23/06
00426 
00427         /***----For testing the SCC----***/
00428         int mixed;
00429 
00430         /***---- For finding the separation and attachment points ----***/
00431         icVector2 evec[2];
00432         icMatrix2x2 Jacobian;     //for calculate the decomposition of the Jacobian
00433         int valid;
00434 
00436         icVector2 intersections[2];  //we store only the recent two intersections
00437         int num_intersections;
00438         //double pre_length;
00439 
00440         Edge *next;
00441 }Edge;
00442 
00443 typedef struct Vertex {
00444         double x,y,z;             //the coordinates of the vertex under global frame
00445         double bx, by;        //jitter the coordinates a little bit
00446         double nx,ny,nz;
00447         double prob_on_path;
00448         void *other_props;        //other properties 
00449         icVector3 normal;         //normal at the vertex
00450 
00451         int *edges_id;            //edges incident to current vertex
00452         int Num_edge;             //number of edges
00453         Edge **edges;             //store the addresses of the edges incident to the vertex
00454         
00455         /*---------Variables for corner table---------------*/
00456         int *Corners;             //store the indexes of those corners associate with the vertexs
00457         int Num_corners;          //Number of the corners
00458 
00459         /*---------Variables for region smoothing---------------*/
00460         int OnBoundary; 
00461         int InRegion;
00462         int VertID;               //*Index in the whole object vertices list
00463         int RegionListID;         //Index in the inner vertices list
00464         
00465         /*---------Variables for pair cancellation---------------*/
00466         int repell_flag;          //for repeller neighborhood | 0--unknown, 1--on boundary, 2-- in region
00467         int attract_flag;         //for attractor neighborhood | 0--unknown, 1--on boundary, 2-- in region
00468 
00470         int which_line;
00471         double distance;
00472         //int visited;
00473         bool visited;
00474         unsigned char tau_visited;
00475 
00476         /*----------Variable for finding the separation and attachment points --------------*/
00477         icVector2 vec;           //variable to store the vector on that vertex under global frame
00478         icVector2 vec_J;
00479         icVector2 evec[2];
00480         double length[3];
00481 
00482         icMatrix2x2 Jacobian;    /*we will calculate it according to the Jacobian around its one ring neighbor*/
00483         /*eigen vectors*/
00484         icVector2 major, minor;  /*for visualization only*/
00485         double major_ang, minor_ang;
00486         double tensor_major_ang;
00487         bool major_cos, major_sin, minor_cos, minor_sin;
00488         icVector2 tran_vec;      /*transfer eigen vector to a real vector field*/
00489 
00490         double mag_speed;
00491 
00492         /*------------------------------------------------------*/
00493         int *connected_limitcycle;
00494         int num_connectedlimitcycle;
00495         
00496         /*------------For local tracing----------------*/
00497         double *Anglist;   //store the angle allocated for each triangle on the tangent plane
00498 
00499         /*------------For adaptive \tau-----------*/ //03/15/06
00500         float tau[2];  /*previous two \tau for adaptive adjust \tau*/
00501         icVector2 endp[2];    /*the global coordinates of the end point*/
00502         int end_tri[2];       /*the triangle contains the end point*/
00503         bool end1_ornot;      /*tell program which tau it should use, 0--tau[0], 1--tau[1]*/
00504         bool done;           /*mark if it has been traced*/
00505 
00506         /*---- For asymmetric method----*/
00507         float gama_d, gama_r, gama_s;
00508         float hue, saturation;
00509 
00510         /*--- color mapping ---*/
00511         float vf_r, vf_g, vf_b;
00512 
00513         float f_color[3], b_color[3];
00514 
00515         float d_color[3];  /*for density visualization*/
00516         int s_count;       /*the number of the samples associated with this vertex*/
00517 
00518 
00519 } Vertex;
00520 
00521 typedef struct Face {
00522         unsigned char nverts;        // number of vertices in the list 
00523         int *verts;                  // indices of the vertices associated with current face list 
00524         void *other_props;           //other properties 
00525         double area;                 //area of the face
00526         double length[3], angle[3];  //???
00527         int nvisible;
00528         icVector3 normal;           //normal of the face
00529         //icVector3 center;           //
00530 
00531         Edge *edges[3];             //store the address of the associated edges
00532 
00534         int index;                  //index of current face
00535 
00536         icVector2 LX;               //local frame , x axis
00537         icVector2 LY;               //local frame,  y axis
00538 
00539         double xy[3][2];            //store the coordinates of its three vertices under local frame
00540 
00541         icVector2 direct_vec[3];    //store the directional vectors in local frame, we have 3 vectors for each triangle
00542 
00543         icMatrix2x2 Jacobian;       //every triangle mesh will have a local linear vector field (Jacobian Matrix)
00544 
00545         /*---------Variables for pair cancellation---------------*/
00546         int repell_inregion;        //whether the triangle is inside the repeller neighborhood
00547         int attract_inregion;       //whether the triangle is inside the attractor neighborhood
00548 
00549         int contain_singularity;    //flag to mark whether this triangle containing a singularity or not
00550         int singularity_index;      //id of the singularity contained by current triangle
00551 
00553         int inDesignCellCycle;
00554 
00555         int contain_separatrix;     //for separatrix editing (grow region)1/3/06
00556         int fence_flag;             //to set fence to prevent the region growing crossing this triangle
00557 
00559         int access_count;           //record the times that the local tracing accessing
00560         int discard;                //if it is not a good condition triangle, reuse it as boundary flag 3/16/06
00561 
00562         /*------------For streamline placement-----------*/ //2/18/06
00563         int *trajlist;              //a list of the trajectory indices that pass through the triangle
00564         int num_passing_trajs;      //number of the trajectories passing through the triangle
00565 
00566         /*----------------------------------------------*/
00567         int which_SSC, pre_SCC;              //which strongly component it belongs to
00568 
00569         /*----------For the Jacobian of the triangle--------- 07/17/06 */
00570         icVector2 eigen[2];
00571         double evalues[2];
00572         double center[2];           //store the center of the triangle
00573 
00574         /*----------For degenerate point detection (temp) ---------- 09/18/2007 */
00575         unsigned char degenerate_type;
00576 
00577         /*------------For streamline placement, using samplin point-----------*/ //copy at 07/22/06
00578         SampleListInTriangle *samplepts;
00579         int *sampleindex;
00580         int num_samplepts;
00581         int MaxSampNum;
00582 
00583 } Face;
00584 
00585 typedef struct Corner{
00586         int index;
00587         double angle;
00588         Edge *edge[2];    //two edges associated with this corner
00589 
00591         int v;            //the ID of the vertex of the corner
00592         int n;
00593         int p;
00594         int t;            //the triangle the corner belongs to
00595         Edge *e;          //the opposite edge of the corner
00596         int o;            //the index of its opposite corner
00597         int ot;           //the index of its opposite triangle for traversal 2/9/05
00598 
00599         int Edge_count;   //special variable for edges search 1/21/05
00600 
00601         /*----------------------------------------------------------*/
00603         double BeginAng, EndAng;
00604         double r;
00605         int orient;
00606 }Corner;
00607 
00608 typedef struct Polygon3D {
00609         /*unsigned */int nverts, nfaces, nedges;   //number of vertices, faces, edges respectively
00610         Vertex **vlist;                        //list of vertices
00611         Face **flist;                          //list of faces
00612         //PlyOtherProp *vert_other,*face_other;  
00613         double area;
00614         double radius;                         //radius of the bounding sphere of the object
00615         double ave_edge_length;
00616         icVector3 center;                      //the center of the object
00617 
00618         Edge *elist;              //This is a different link from vertices and faces to store the unknown edges
00619         Edge **edgelist;
00620 
00622         Corner **clist;
00623         int ncorners;
00624 
00625 } Polygon3D;
00626 
00627 
00628 // Streamline
00629 typedef struct Seed{
00630         //double pos[3];                //the coordinates of the seed point
00631         double pos[2];                  //the coordinates of the seed point
00632         int triangle;                   //the triangle contains the seed point
00633         //int which_traj;                 //record which trajectory it locates on
00634         unsigned char state;            //0—active;1—inactive; 2—can not growing
00635         double weight;
00636 }Seed; // end of Seed structure
00637 
00638 enum road_type{
00639         MINOR,
00640         MAJOR,
00641         HIGHWAY,
00642         BOUNDARY
00643         //FREEWAY
00644         //PLAIN,
00645 };
00646 
00647 
00648 
00649 typedef struct LineSeg{
00650         int Triangle_ID;                    //which triangle this line segment locates in
00651         double start[2], end[2];            //local coordinates for start and end points
00652         double gstart[2], gend[2];          //global coordinates for start and end points
00653         double length;                      //we may need to store the length of the line segment
00654 } LineSeg;
00655 
00656 typedef struct CurvePoints{
00657         double lpx, lpy;
00658         double gpx, gpy;
00659         double length;
00660         int triangleid;
00661 }CurvePoints;
00662 
00663 
00664 
00665 
00666 class SeedList{
00667 public:
00668         Seed **seeds;
00669         int nseeds;
00670         int curMaxNumSeeds;
00671         double max_weight, min_weight;
00672 
00673         // The similar list operations
00674         SeedList(int initsize = 3000) //construction
00675         {
00676                 seeds = (Seed **)malloc(sizeof(Seed *)*initsize);
00677                 curMaxNumSeeds = initsize;
00678                 nseeds = 0;
00679 
00680                 if(seeds == NULL)
00681                 {
00682                         //char rout[256], var[256];
00683                         //sprintf(rout, "%s", "SeedList Constructor");
00684                         //sprintf(var, "%s", "seeds");
00685 
00686                         //write_mem_error(rout, var, 0);
00687                         curMaxNumSeeds = 0;
00688                         exit(-1);
00689 
00690                 }
00691                 int i;
00692                 for(i = 0; i < initsize; i++)
00693                         seeds[i] = NULL;
00694         } 
00695 
00696         ~SeedList()
00697         {
00698                 int i;
00699                 for(i = 0; i < curMaxNumSeeds; i++)
00700                 {
00701                         if(seeds[i] != NULL)
00702                                 free(seeds[i]);
00703                 }
00704                 free(seeds);
00705         }
00706 
00707         inline void copy_otherseedList(SeedList *otherseeds)
00708         {
00709                 int i;
00710                 if(otherseeds->nseeds>curMaxNumSeeds)
00711                 {
00712                         if(!extend(otherseeds->nseeds-curMaxNumSeeds))
00713                                 exit(-1);
00714                 }
00715 
00716                 /*copy element by element*/
00717                 for(i=0;i<otherseeds->nseeds;i++)
00718                 {
00719                         if(seeds[i]==NULL)
00720                                 seeds[i]=(Seed *) malloc(sizeof(Seed));
00721 
00722                         seeds[i]->pos[0]=otherseeds->seeds[i]->pos[0];
00723                         seeds[i]->pos[1]=otherseeds->seeds[i]->pos[1];
00724 
00725                         seeds[i]->triangle=otherseeds->seeds[i]->triangle;
00726                         seeds[i]->state=otherseeds->seeds[i]->state;
00727                         seeds[i]->weight=otherseeds->seeds[i]->weight;
00728                 }
00729                 nseeds=otherseeds->nseeds;
00730         }
00731 
00732         inline void copyandappend_otherseedList(SeedList *otherseeds)
00733         {
00734                 int i;
00735                 if(otherseeds->nseeds+nseeds>curMaxNumSeeds)
00736                 {
00737                         if(!extend(otherseeds->nseeds+nseeds-curMaxNumSeeds))
00738                                 exit(-1);
00739                 }
00740 
00741                 /*copy element by element*/
00742                 for(i=nseeds;i<nseeds+otherseeds->nseeds;i++)
00743                 {
00744                         if(seeds[i]==NULL)
00745                                 seeds[i]=(Seed *) malloc(sizeof(Seed));
00746 
00747                         seeds[i]->pos[0]=otherseeds->seeds[i-nseeds]->pos[0];
00748                         seeds[i]->pos[1]=otherseeds->seeds[i-nseeds]->pos[1];
00749 
00750                         seeds[i]->triangle=otherseeds->seeds[i-nseeds]->triangle;
00751                         seeds[i]->state=otherseeds->seeds[i-nseeds]->state;
00752                 }
00753                 nseeds+=otherseeds->nseeds;
00754         }
00755 
00756         //add a new vertex to the end of the list, if it succeeds, return true
00757         inline bool append(Seed *s)
00758         {
00759                 if(isFull ())
00760                         if(!extend(100))
00761                                 return false;             //if not enough memory available, return false
00762                 seeds[nseeds] = s;
00763                 //copyElem(s, polist[nporbits]);
00764                 nseeds++;
00765                 return true;
00766         } 
00767 
00768         /*  insert a new seed to the proper position of the list according to its weight  */
00769         inline bool sorted_add(Seed *s)
00770         {
00771                 if(nseeds>=curMaxNumSeeds)
00772                 {
00773                         if(!extend())
00774                                 //exit(-1);
00775                                         return false;
00776                 }
00777 
00778                 /*sorted insert!*/
00779                 int i, pos=0;
00780                 for(i=0; i<nseeds; i++)
00781                 {
00782                         if(s->weight>seeds[i]->weight)
00783                         {
00784                                 pos = i;
00785                                 break;
00786                         }
00787                 }
00788                 if(i>=nseeds) pos=nseeds;
00789                 for(i=nseeds; i>pos; i--)
00790                         seeds[i]=seeds[i-1];
00791                 seeds[pos]=s;
00792 
00793                 nseeds ++;
00794                 return true;
00795         }
00796 
00797         inline void update_max_min_weights()
00798         {
00799                 int i;
00800                 if(nseeds==0) return;
00801                 max_weight=min_weight=seeds[0]->weight;
00802                 for(i=1;i<nseeds;i++)
00803                 {
00804                         if(seeds[i]->weight>max_weight) max_weight=seeds[i]->weight;
00805                         if(seeds[i]->weight<min_weight) min_weight=seeds[i]->weight;
00806                 }
00807         }
00808 
00809         inline bool del_End() //delete the vertex at the end of the list
00810         {
00811                 if(isEmpty())  return false;
00812                 nseeds --;
00813                 return true;
00814         } 
00815 
00816         inline void copy_Elem(Seed *to, Seed *from)
00817         {
00818                 to->pos[0]=from->pos[0];
00819                 to->pos[1]=from->pos[1];
00820                 to->triangle=from->triangle;
00821                 to->state=from->state;
00822         }
00823 
00824         //delete the corresponding  vertex, if it succeeds, return true
00825         inline bool del_Node(Seed *s) 
00826         {
00827                 if(isEmpty())  return false;
00828 
00829                 //find the vertex, if find it, delete and move the following vertices forward
00830                 //otherwise, return false;
00831 
00832                 int i, pos = -1;
00833 
00834                 for(i = 0; i < nseeds; i++)
00835                 {
00836                         if(seeds[i] == s)
00837                         {
00838                                 pos = i;
00839                                 break;
00840                         }
00841                 }
00842 
00843                 if(pos == -1) return false;
00844 
00845                 //delete it
00846                 for(i = pos; i < nseeds-1; i++)
00847                 {
00848                         //we need a copy function
00849                         copy_Elem(seeds[i], seeds[i+1]);
00850                 }
00851 
00852                 nseeds--;
00853 
00854                 return true;
00855         } 
00856 
00857         inline bool del_Node_byindex(int pos) 
00858         {
00859                 int i;
00860                 if(isEmpty())  return false;
00861 
00862                 //find the vertex, if find it, delete and move the following vertices forward
00863                 //otherwise, return false;
00864 
00865                 if(pos == -1) return false;
00866 
00867                 //delete it
00868                 for(i = pos; i < nseeds-1; i++)
00869                 {
00870                         //we need a copy function
00871                         copy_Elem(seeds[i], seeds[i+1]);
00872                 }
00873 
00874                 nseeds--;
00875 
00876                 return true;
00877         } 
00878 
00879         inline bool isEmpty()  //judge whether the list is empty
00880         {
00881                 if(nseeds == 0)   return true;
00882                 return false;
00883         }
00884 
00885         inline bool isFull()
00886         {
00887                 if(nseeds == curMaxNumSeeds) return true;
00888                 return false;
00889         }
00890 
00891         //extend the original list, if it succeeds, return true
00892         inline bool extend(int step = 100)
00893         {
00894                 Seed **temp = seeds;
00895                 seeds = (Seed **) malloc(sizeof(Seed *) * (curMaxNumSeeds + step));
00896                 if( temp == NULL)
00897                 {
00898                         //fail
00899                         //char rout[256], var[256];
00900                         //sprintf(rout, "%s", "SeedList::extend");
00901                         //sprintf(var, "%s", "seeds");
00902 
00903                         //write_mem_error(rout, var, 1);
00904                         curMaxNumSeeds = 0;
00905                         seeds = temp;
00906                         exit(-1);
00907                         return false;
00908                 }
00909 
00910                 int i;
00911                 for(i = 0; i < curMaxNumSeeds; i++)
00912                         seeds[i] = temp[i];
00913 
00914                 for(i=curMaxNumSeeds; i<curMaxNumSeeds+step; i++)
00915                         seeds[i]=NULL;
00916 
00917                 curMaxNumSeeds += step;
00918 
00919                 free(temp);
00920                 return true;
00921         }
00922 
00923         inline void reset()
00924         {
00925                 nseeds = 0;
00926         }
00927 }; //end of SeedList class
00928 
00930 typedef struct SamplePt{
00931         //double gpt[3];
00932         double gpt[2];
00933         int triangle;
00934         int traj;                                //which trajectory this sample falls on
00935 }SamplePt; //end of SamplePt class
00936 
00937 class SamplePtList{
00938 public:
00939         SamplePt **samples;
00940         int nsamples;
00941         int curMaxNumSamplePts;
00942 
00943         SamplePtList(int initsize = 1000) //construction
00944         {
00945                 samples = (SamplePt **)malloc(sizeof(SamplePt *)*initsize);
00946                 curMaxNumSamplePts = initsize;
00947                 nsamples = 0;
00948 
00949                 if(samples == NULL)
00950                 {
00951                         //char rout[256], var[256];
00952                         //sprintf(rout, "%s", "SamplePtList Constructor");
00953                         //sprintf(var, "%s", "samples");
00954 
00955                         //write_mem_error(rout, var, 0);
00956                         curMaxNumSamplePts = 0;
00957                         exit(-1);
00958                 }
00959 
00960                 for(int i = 0; i < initsize; i++)
00961                         samples[i] = NULL;
00962         } 
00963 
00964         ~SamplePtList()
00965         {
00966                 if(samples!= NULL)
00967                 {
00968                         for(int i = 0; i < curMaxNumSamplePts; i++)
00969                         {
00970                                 if(samples[i] != NULL)
00971                                         free(samples[i]);
00972                         }
00973                         free(samples);
00974                 }
00975         }
00976 
00977         //add a new vertex to the end of the list, if it succeeds, return true
00978         inline bool append(SamplePt *s)
00979         {
00980                 if(isFull ())
00981                         if(!extend(100))
00982                                 return false;             //if not enough memory available, return false
00983                 samples[nsamples] = s;
00984                 //copyElem(s, polist[nporbits]);
00985                 nsamples++;
00986                 return true;
00987         } 
00988 
00989         inline bool del_End() //delete the vertex at the end of the list
00990         {
00991                 if(isEmpty())  return false;
00992                 nsamples --;
00993                 return true;
00994         } 
00995 
00996         inline void copy_Elem(SamplePt *s, SamplePt *d)
00997         {
00998         }
00999 
01000         //delete the corresponding  vertex, if it succeeds, return true
01001         inline bool del_Node(SamplePt *s) 
01002         {
01003                 if(isEmpty())  return false;
01004 
01005                 //find the vertex, if find it, delete and move the following vertices forward
01006                 //otherwise, return false;
01007 
01008                 int i, pos = -1;
01009 
01010                 for(i = 0; i < nsamples; i++)
01011                 {
01012                         if(samples[i] == s)
01013                         {
01014                                 pos = i;
01015                                 break;
01016                         }
01017                 }
01018 
01019                 if(pos == -1) return false;
01020 
01021                 //delete it
01022                 for(i = pos; i < nsamples-1; i++)
01023                 {
01024                         //we need a copy function
01025                         copy_Elem(samples[i], samples[i+1]);
01026                 }
01027 
01028                 nsamples--;
01029 
01030                 return true;
01031         } 
01032 
01033         inline bool isEmpty()  //judge whether the list is empty
01034         {
01035                 if(nsamples == 0)   return true;
01036                 return false;
01037         }
01038 
01039         inline bool isFull()
01040         {
01041                 if(nsamples == curMaxNumSamplePts) return true;
01042                 return false;
01043         }
01044 
01045         //extend the original list, if it succeeds, return true
01046         inline bool extend(int step = 100)
01047         {
01048                 SamplePt **temp = samples;
01049                 samples = (SamplePt **) malloc(sizeof(SamplePt *) * (curMaxNumSamplePts + step));
01050                 if( temp == NULL)
01051                 {
01052                         //fail
01053                         //char rout[256], var[256];
01054                         //sprintf(rout, "%s", "SamplePtList::extend");
01055                         //sprintf(var, "%s", "samples");
01056 
01057                         //write_mem_error(rout, var, 1);
01058                         curMaxNumSamplePts = 0;
01059                         samples = temp;
01060                         exit(-1);
01061                         return false;
01062                 }
01063 
01064                 int i;
01065                 for(i = 0; i < curMaxNumSamplePts; i++)
01066                         samples[i] = temp[i];
01067                 for(i = curMaxNumSamplePts; i < curMaxNumSamplePts+step; i++)
01068                         samples[i] = NULL;
01069                 curMaxNumSamplePts += step;
01070 
01071                 free(temp);
01072                 return true;
01073         }
01074 
01075         inline void reset()
01076         {
01077                 nsamples = 0;
01078         }
01079 }; //end of SamplePtList class
01080 
01081 class DynList_Int{
01082 public:
01083         //member variables
01084         int *elems;
01085         int  nelems;
01086         int  curMaxNum;
01087         int  extendstep;
01088 
01089         //member functions
01090         //constructions and destruction
01091         DynList_Int(int MaxNum = 500) 
01092         {
01093                 elems = new int [MaxNum];
01094                 curMaxNum = MaxNum;
01095                 nelems = 0;
01096         }
01097         ~DynList_Int()
01098         {delete [] elems; }
01099 
01100         inline bool extend(int step = 100) 
01101         {
01102                 int *temp = elems;
01103                 elems = new int[curMaxNum + step];
01104                 if(elems == NULL)
01105                 {
01106                         elems = temp;
01107                         return false;
01108                 }
01109 
01110                 for(int i = 0; i < curMaxNum; i++)
01111                         elems[i] = temp[i];
01112 
01113                 curMaxNum += step;
01114 
01115                 delete [] temp;
01116                 return true;
01117         }
01118 
01119         inline bool add_New(int t)
01120         {
01121                 if(is_Full())
01122                 {
01123                         if(!extend())
01124                         {
01125                                 return false;
01126                         }
01127                 }
01128 
01129                 if(!is_repeated(t))
01130                 {
01131                         elems[nelems] = t;
01132                         nelems++;
01133                         return true;
01134                 }
01135 
01136                 return false;
01137         }
01138 
01139         inline bool add_New_2(int t)
01140         {
01141                 if(nelems>=curMaxNum)
01142                 {
01143                         if(!extend())
01144                         {
01145                                 return false;
01146                         }
01147                 }
01148 
01149                 //if(!is_repeated_elem(elems, t, nelems))
01150                 //{
01151                 //      elems[nelems] = t;
01152                 //      nelems++;
01153                 //      return true;
01154                 //}
01155                 elems[nelems] = t;
01156                 nelems++;
01157                 return true;
01158 
01159                 return false;
01160         }
01161 
01162         inline bool is_Full()
01163         {
01164                 return nelems>=curMaxNum;
01165         }
01166 
01167         inline bool  del_Elem(int t)
01168         {
01169                 int i, pos = 0;
01170                 for(i = 0; i < nelems; i++)
01171                 {
01172                         if(elems[i] == t)
01173                         {
01174                                 pos = i;
01175                                 break;
01176                         }
01177                 }
01178                 if(pos >= nelems)
01179                         return false;
01180 
01181                 for(i = pos; i < nelems-1; i++)
01182                         elems[i] = elems[i+1];
01183 
01184                 nelems--;
01185                 return true;
01186         }
01187 
01188 
01189         inline bool  del_Last()
01190         {
01191                 if(nelems <= 0) return false;
01192                 nelems--;
01193                 return true;
01194         }
01195 
01196         inline bool  is_repeated(int newelem)
01197         {
01198                 int i;
01199                 for(i=0; i<nelems; i++)
01200                 {
01201                         if(elems[i] == newelem)
01202                                 return true;
01203                 }
01204                 return false;
01205         }
01206 };
01207 
01208 
01209 
01210 
01211 
01212 
01213 
01214 
01215 
01216 
01217 
01218 
01219 
01220 
01221 
01222 
01226 //
01227 #endif // !1


tensor_field_nav_core
Author(s): Lintao Zheng, Kai Xu
autogenerated on Thu Jun 6 2019 19:50:56