pfs.c

Go to the documentation of this file.
00001 
00002 /*
00003 ** ---------------------------------------------------------------
00004 **
00005 ** @name Parametrized Faceted Surface module
00006 **
00007 ** ---------------------------------------------------------------
00008 **
00009 ** @date    20-Nov-2006
00010 ** @author  Luiz F. Martha
00011 ** @version 1.0
00012 **
00013 ** ---------------------------------------------------------------
00014 ** pfs.c - Parametrized Faceted Surface module.
00015 **
00016 ** Description:
00017 ** ---------------------------------------------------------------
00018 **
00019 ** This module contains functions to represent a typical faceted 
00020 ** (triangulated) surface mesh data and functions to create a 
00021 ** two-dimensional parametric space associated to the faceted 
00022 ** surface.
00023 ** Basically, a pair of surface parametric values are associated 
00024 ** to each node in the mesh.  This is mainly based on the wrk
00025 ** of Levy, Petitjean, Ray, and Maillot, "Least squares conformal
00026 ** maps for automatic texture atlas generation," SIGRAPH 
00027 ** proceedings, 2002
00028 ** The local data structure consists of a node (vertex) vector
00029 ** with nodal coordinates and node-node adjacency relationships,
00030 ** and an element (face) vector with nodal connectivity.
00031 **
00032 ** The API of this module is described in file "pfs.h".
00033 **
00034 ** ---------------------------------------------------------------
00035 **
00036 ** Created:    17-Jan-2005    Luiz F. Martha
00037 **    Stolen from old pfs module based on the work of
00038 **    Michael Floater: "Parametrization and smooth approximation 
00039 **    of surface triangulation", Computer Aided Geometric Design, 
00040 **    vol. 14, pp. 231-250, 1997.
00041 **    Based on ArbSurfaceMapping.cpp by Wash.
00042 **
00043 ** Modified:   17-Feb-2006    Alexandre A. Del Savio
00044 **    Created the functions pfsProjectOn, pfsDistElem2Point,
00045 **    pfsGetParPoint, pfsMapUV and pfsArea3d.
00046 **    These functions were based on nSurfacePFS package, by 
00047 **    William Lira and Antonio Miranda.
00048 **
00049 ** Modified:   20-Feb-2006    Alexandre A. Del Savio
00050 **    Created the functions pfsGetJacobian, pfsUnMapUV,
00051 **    pfsGetJac, pfsArea2d, pfsIsParPtOnBound, pfsIsParPtInside, 
00052 **    and pfsSnapParPtToBound.
00053 **
00054 ** Modified:   22-Feb-2006    Alexandre A. Del Savio
00055 **    Modified the function pfsGetJacobian. It passed to
00056 **    return the components of the normal vector of  
00057 **    element face where is the point.
00058 **
00059 ** Modified:   22-Feb-2006    William W. M. Lira
00060 **    Created the functions pfsEval and pfsGet3dPoint.
00061 **    These functions were based on nSurfacePFS package, by 
00062 **    William Lira and Antonio Miranda.
00063 **
00064 ** Modified:   23-Feb-2006    Alexandre A. Del Savio
00065 **    Modified the function pfsAddElem. It passed to have
00066 **    a return. If there is no active surface it returns a
00067 **    false (0) status, otherwise it returns a true (1) 
00068 **    status.
00069 **
00070 ** Modified:   27-Jul-2006    Luiz F. Martha
00071 **    Created local function pfsNodeConstrNormal.
00072 **    Modified function pfsAddAdjNode to order adjacent 
00073 **    nodes around a reference node taking into account an
00074 **    average normal vector that considers the the given 
00075 **    element normal (if the element is not null) and
00076 **    normal vectors of the adjacent elements in the list 
00077 **    of adjacent nodes (it uses the created function 
00078 **    pfsNodeConstrNormal).
00079 **
00080 ** Modified:   30-Jul-2006    Luiz F. Martha
00081 **    Created exported functions pfsItrNumLoops, pfsItrFirstLoopNode,
00082 **    pfsItrNextLoopNode.
00083 **    Created vector of first loop's node.
00084 **    Modified functions pfsIsParPtOnBound, pfsIsParPtInside, and 
00085 **    pfsSnapParPtToBound such that the use loop data structure 
00086 **    instead of the dces package.
00087 **    Created NODE_MARKED type.
00088 **    Created local functions pfsMarkBdryNodes, pfsUnmarkLoopNodes,
00089 **    and pfsBuildLoopList.
00090 **
00091 ** Modified:   31-Aug-2006    Luiz F. Martha
00092 **    Created exported function pfsCompleteParSpace to compute 
00093 **    parametric bounding boxes of elements, to build the R-tree 
00094 **    of elements indexed by parametric bounding boxes and to compute 
00095 **    node Jacobians.
00096 **    Modified function pfsSolveSurfPar to not perform these tasks.
00097 **    Created local function pfsNormalizeParVals and got rid of local
00098 **    functions pfsMapUV and pfsUnMapUV.
00099 **    Replaced function pfsDistElem2Point by function pfsDistPntCurElem.
00100 **    Replaced function pfsGetParPoint by function pfsParPntCurElem.
00101 **    Modified function pfsProjectOn to use functions pfsDistPntCurElem
00102 **    and pfsParPntCurElem.
00103 **    Replaced function pfsGet3dPoint by function pfs3dPntCurElem.
00104 **    Modified function pfsEval to use pfs3dPntCurElem.
00105 **    Replaced function pfsGetJac by function pfsParDerivCurElem.
00106 **    Modified function pfsGetJacobian to use pfsParDerivCurElem.
00107 **    Created exported function pfsSetCurrElem.
00108 **
00109 ** Modified:   20-Sep-2006    Gisele Cunha Holtz
00110 **    Created exported function pfsShot and all the related 
00111 **    local functions.
00112 **
00113 ** Modified:   26-Sep-2006    Luiz F. Martha
00114 **    Modified names of functions and did some clean up.
00115 **
00116 ** Modified:   05-Oct-2006    Gisele Cunha Holtz
00117 **    Criada a função pfsIsPntInElem. Modificada a função pfsArea3d,
00118 **    que passou a receber a normal da area e a retornar a área com
00119 **    sinal de acordo com a normal recebida.
00120 **
00121 ** Modified:   20-Nov-2006    Luiz F. Martha
00122 **    Created exported function pfsSnapToBound.
00123 **    Modified functions pfsGetJacobian and pfsEval such that they
00124 **    reject points outside current active surface.
00125 **    Did some clean up.
00126 **
00127 ** Modified:   09-July-2007    Gisele Cunha Holtz
00128 **    Foram realizadas alterações para evitar problemas com a 
00129 **    tolerância:
00130 **    Modificada a função pfsParPntCurElem para retornar o status
00131 **    de que um ponto está dentro de um elemento apenas quando
00132 **    o ponto estiver dentro no espaço cartesiano e no paramétrico.
00133 **    A função pfsUpdateShotLen passou a verificar se o 
00134 **    comprimento restante do tiro é menor que a tolerância.
00135 **    Na função pfsChkProxElemEdge foi feita uma pequena alteração
00136 **    na verificação se o ponto está sobre um nó. Além disso,
00137 **    adicionado um teste para certificar que a projeção do ponto
00138 **    sobre a aresta está realmente sobre a aresta.
00139 **    Criada a função pfsParPntCurElemAttract que é similiar a 
00140 **    pfsParPntCurElem, exceto por corrigir a coordenada do ponto
00141 **    qdo o ponto está dentro do triângulo. 
00142 **    Removida a funçao pfsIsPntInElem e substituídas suas chamadas por
00143 **    pfsParPntCurElem. Criadas as funções pfs3dGetAreaCoord e 
00144 **    pfsParGetAreaCoord.
00145 */
00146 
00147 #define _PFS_C
00148 
00149 /*
00150 ** ---------------------------------------------------------------
00151 ** Global variables and symbols:
00152 */
00153 #include <stdlib.h>
00154 #include <stdio.h>
00155 #include <math.h>
00156 
00157 #include "geo.h"
00158 #include "pfs.h"
00159 #include "amr3b.h"
00160 
00161 /*
00162 ** ---------------------------------------------------------------
00163 ** Local definitions and variables:
00164 */
00165 
00166 #define ITER_TOLER 0.0001
00167 
00168 #define TOLER 1e-5
00169 
00170 #define COL_TOLER 1e-5 
00171 
00172 #ifndef ABS
00173 #define ABS(x) (((x) < 0.0)? -(x): (x))
00174 #endif
00175 
00176 #ifndef MAX
00177 #define MAX(a,b) (((a) > (b)) ? (a) : (b))
00178 #endif
00179 
00180 #ifndef Len2
00181 #define Len2(x,y) sqrt((double)(((x)*(x))+((y)*(y))))
00182 #endif
00183 
00184 #ifndef Len3
00185 #define Len3(x,y,z) sqrt((double)(((x)*(x))+((y)*(y))+((z)*(z))))
00186 #endif
00187 
00190 #define DET2D(a,b,c,d)   (((a)*(d))-((b)*(c)))
00191 
00195 #define X_CROSS_LINE_LINE(x1,y1,x2,y2,x3,y3,x4,y4) \
00196         DET2D( DET2D(x1,y1,x2,y2), x1-x2, DET2D(x3,y3,x4,y4), x3-x4) / \
00197         DET2D(x1-x2,y1-y2,x3-x4,y3-y4)
00198 #define Y_CROSS_LINE_LINE(x1,y1,x2,y2,x3,y3,x4,y4) \
00199         DET2D( DET2D(x1,y1,x2,y2), y1-y2, DET2D(x3,y3,x4,y4), y3-y4) / \
00200         DET2D(x1-x2,y1-y2,x3-x4,y3-y4)
00201 
00205 #define X_CROSS_LINE_SHOT(x1,y1,x2,y2,x0,y0,xS,yS) \
00206         DET2D( DET2D(x1,y1,x2,y2), x1-x2, DET2D(xS,yS,x0,y0), xS) / \
00207         DET2D(x1-x2,y1-y2,xS,yS)
00208 #define Y_CROSS_LINE_SHOT(x1,y1,x2,y2,x0,y0,xS,yS) \
00209         DET2D( DET2D(x1,y1,x2,y2), y1-y2, DET2D(xS,yS,x0,y0), yS) / \
00210         DET2D(x1-x2,y1-y2,xS,yS)
00211 
00212 
00214 enum {
00215  NODE_INTERIOR,
00216  NODE_BOUNDARY,
00217  NODE_MARKED
00218  };
00219 
00220 enum {
00221  NODE = 1,
00222  EDGE = 2,
00223  FACE = 4,
00224  LOOP = 8,
00225  FREE_FACE = 16
00226  };
00228 typedef struct _pfselem {
00230   int           inc[3];
00232   PFSGeoPoint      normal;
00234   PFSGeoPoint      center;
00236   double          area;
00238   double       W[3][2];
00240   PFSGeoPoint    min3dbox;
00242   PFSGeoPoint    max3dbox;
00244   PFSGeoSurfPar minparbox;
00246   PFSGeoSurfPar maxparbox;
00247  } PfsElem;
00248 
00250 typedef struct _pfsadjnode {
00252   struct _pfsadjnode  *next;
00254   int                 id;
00257   PfsElem             *elem;
00260   int                 refcnt;
00263   double           AtA[2][2];
00264  } PfsAdjNode;
00265 
00267 typedef struct _pfsnode {
00269   PFSGeoPoint            coord;
00271   PFSGeoPoint            normal;
00273   PFSGeoPoint            ddu;
00275   PFSGeoPoint            ddv;
00277   PFSGeoSurfPar          par;
00279   int                 degree;
00281   double              AtA[2][2];
00283   struct _pfsadjnode  *adj_head;
00285   int                 type;
00286  } PfsNode;
00287 
00289 typedef struct _pfssurf {
00291   int          numnodes;
00293   int          numelems;
00295   int          numloops;
00298   PfsNode      *nodelist;
00300   void         *elm3d_tree;
00302   void         *elm2d_tree;
00304   int          *looplist;
00306   int          *sol_order;
00308   int maxnodes;
00310   double box_xmin;
00312   double box_xmax;
00314   double box_ymin;
00316   double box_ymax;
00318   double box_zmin;
00320   double box_zmax;
00322   double box_umin;
00324   double box_umax;
00326   double box_vmin;
00328   double box_vmax;
00331   PfsElem *ref_elem;
00334   int     ref_node;
00337   double  iter_toler;
00338 
00339 } PfsSurf;
00340 
00341 /* Active surface data pointer.
00342  */
00343 static PfsSurf *pfs;
00344 
00345 /* Index of current element and current element node for traversal.
00346  */
00347 static int cur_elemnode;
00348 
00349 static PfsElem   *cur_elem = NULL;
00350 static PfsElem *curr_ielem = NULL;
00351 int _loop_ = 0;
00352 
00353 /*
00354 ** ---------------------------------------------------------------
00355 ** Private functions: 
00356 */
00357 static void pfs3dGetAreaCoord( double x, double y, double z,
00358                                double* xn, double* yn, double* zn,
00359                                double* b0, double* b1, double* b2 );
00360 static void pfsParGetAreaCoord( double u, double v,
00361                                 double* un, double* vn, 
00362                                 double* b0, double* b1, double* b2 );
00363 static void pfsNodeConstrNormal( int ref_id, PfsElem *elem, PFSGeoPoint *normal );
00364 static int  pfsAddAdjNode( int ref_id, int adj_id, PfsElem* elem );
00365 static int  pfsBuildNodeAdj( void );
00366 static int  pfsChkBdryNode( int id );
00367 static void pfsClassifyNodes( void );
00368 static int  pfsOrderBdryNodeAdj( int id );
00369 static int  pfsOrderAllBdryNodeAdj( void );
00370 static void pfsMarkBdryNodes( void );
00371 static void pfsUnmarkLoopNodes( int ref_id );
00372 static void pfsBuildLoopList( void );
00373 static void pfsDelNodeList( PfsSurf *surf );
00374 static void pfsDelElemList( PfsSurf *surf );
00375 static int  pfsGetEdgeAdjElems( int ni, int nj,
00376                                 PfsElem **e_left, PfsElem **e_right );
00377 static void pfsCompute3dBoundBox( void );
00378 static void pfsElemNormal( PfsElem *elem );
00379 static void pfsElemCenter( PfsElem *elem );
00380 static void pfsElemLocalGradients( PfsElem *elem );
00381 static void pfsElem3dBoundBox( PfsElem *elem );
00382 static void pfsNodeNormal( int node );
00383 static void pfsNodeNormals( void );
00384 static void pfsFindRefElem( void );
00385 static void pfsNodeConfMapCoeff( int ref_id );
00386 static void pfsConfMapCoefficients( void );
00387 static void pfsInitParams( void );
00388 static int  pfsCreateNextSolOrderLevel( int lev_begin, int lev_end, int *pos,
00389                                         int *solorder, int *nodevisited );
00390 static void pfsBuildSolOrderVec( void );
00391 static void pfsDelSolOrderVec( PfsSurf *surf );
00392 static void pfsSolve2x2( double a[2][2], double b[2], double *u, double *v );
00393 static void pfsNormalizeParVals( void );
00394 static void pfsComputeParBoundBox( void );
00395 static void pfsElemParBoundBox ( PfsElem *elem );
00396 static void pfsComputeElemParBoundBoxes( void );
00397 static void pfsComputeElemJac  ( PfsElem *elem,
00398                                  double *xdu, double *ydu, double *zdu, 
00399                                  double *xdv, double *ydv, double *zdv );
00400 static void   pfsNodeJacobian  ( int node );
00401 static void   pfsNodeJacobians ( void );
00402 static double pfsArea3d        ( double xa, double ya, double za, 
00403                                  double xb, double yb, double zb,
00404                                  double xc, double yc, double zc,
00405                                  double xn, double yn, double zn );
00406 static double pfsArea2d        ( double u0, double v0,
00407                                  double u1, double v1,
00408                                  double u2, double v2 );
00409 static double pfsDistPntCurElem( PFSGeoPoint *p, PFSGeoPoint *clst );
00410 static int    pfsParPntCurElem ( double x, double y, double z,
00411                                  double *u, double *v );
00412 static int    pfs3dPntCurElem  ( double u, double v,
00413                                  double *x, double *y, double *z );
00414 static int    pfsParDerivCurElem( double u, double v,
00415                                  double *xdu, double *ydu, double *zdu,
00416                                   double *xdv, double *ydv, double *zdv,
00417                                   double *xdw, double *ydw, double *zdw );
00418 static int    pfsClstPtParLine( double ua, double va, double ub, double vb,
00419                                 double u, double v, double *up, double *vp,
00420                                 double *dist );
00421 static int    pfsIsParPtInside    ( PFSGeoSurfPar *p );
00422 static int    pfsIsParPtOnBound   ( PFSGeoSurfPar *p );
00423 static int    pfsSnapParPtToBound ( PFSGeoSurfPar *p );
00424 static int pfsChkProxElemNode( PfsElem *elem, double *u, double *v, int *ni );
00425 static int pfsChkProxElemEdge( PfsElem *elem, double *u, double *v, int *type, 
00426                        int *ni, int *nj );
00427 static int    pfsShotXLine     ( PfsElem *elem, double u0, double v0, 
00428                                  double u_shot, double v_shot,
00429                          int na, int nb, double *u1, double *v1,
00430                          int *type, int *n_inter );
00431 static int pfsNodeShot( PfsElem *init_elem, double u0, double v0, 
00432                         double u_shot, double v_shot,
00433                         PfsElem **end_elem, double *u1, double *v1, 
00434                         int *type, int *ni, int *nj );
00435 static int pfsEdgeShot( PfsElem *init_elem, double u0, double v0, 
00436                         double u_shot, double v_shot,
00437                         PfsElem **end_elem, double *u1, double *v1, 
00438                         int *type, int *ni, int *nj );
00439 static int pfsFaceShot( PfsElem *init_elem, double u0, double v0, 
00440                         double u_shot, double v_shot,
00441                         PfsElem **end_elem, double *u1, double *v1, 
00442                         int *type, int *ni, int *nj );
00443 static int pfsLoopShot( PfsElem *init_elem, double u0, double v0, 
00444                         double u_shot, double v_shot,
00445                         PfsElem **end_elem, double *u1, double *v1, 
00446                         int *type, int *ni, int *nj );
00447 static int pfsUpdateShotLen( double u0, double v0, PFSGeoPoint *p0, 
00448                              double *u1, double *v1, PFSGeoPoint *p1, 
00449                              double *len );
00450 static void pfsFinishFreeFaceShotLen( double u0, double v0, PFSGeoPoint *p0, 
00451                                       double u_shot, double v_shot, double len,
00452                                       double *u1, double *v1, PFSGeoPoint *p1);
00453 static int pfsShotSolve( PfsElem *init_elem, double u0, double v0, 
00454                          PFSGeoPoint p0, double u_shot, double v_shot, 
00455                          PfsElem **end_elem, double *u1, double *v1,
00456                          PFSGeoPoint *p1, int *type, int *ni, int *nj,
00457                          double *len );
00458 
00459 
00460 /*=======================  pfs3dGetAreaCoord  ========================*/
00461 static void pfs3dGetAreaCoord( double x, double y, double z,
00462                                double* xn, double* yn, double* zn,
00463                                double* b0, double* b1, double* b2 )
00464 {
00465  double d;
00466  PFSGeoPoint *normal = &(cur_elem->normal);
00467 
00468  d = pfsArea3d( xn[0], yn[0], zn[0],
00469                 xn[1], yn[1], zn[1],
00470                 xn[2], yn[2], zn[2],
00471                 normal->x, normal->y, normal->z );
00472  *b0 = pfsArea3d( x, y, z, xn[1], yn[1], zn[1], xn[2], yn[2], zn[2],
00473                   normal->x, normal->y, normal->z ) / d;
00474  *b1 = pfsArea3d( x, y, z, xn[2], yn[2], zn[2], xn[0], yn[0], zn[0],
00475                   normal->x, normal->y, normal->z ) / d;
00476  *b2 = pfsArea3d( x, y, z, xn[0], yn[0], zn[0], xn[1], yn[1], zn[1],
00477                   normal->x, normal->y, normal->z ) / d;
00478 }
00479 
00480 /*=====================  pfsParGetAreaCoord  ======================*/
00481 static void pfsParGetAreaCoord( double u, double v,
00482                                 double* un, double* vn, 
00483                                 double* b0, double* b1, double* b2 )
00484 {
00485  double d;
00486 
00487  d = pfsArea2d(un[0], vn[0], un[1], vn[1], un[2], vn[2]);
00488  *b0 = pfsArea2d( u, v, un[1], vn[1], un[2], vn[2]) / d;
00489  *b1 = pfsArea2d( u, v, un[2], vn[2], un[0], vn[0]) / d;
00490  *b2 = pfsArea2d( u, v, un[0], vn[0], un[1], vn[1]) / d;
00491 }
00492 
00493 /*=====================  pfsNodeConstrNormal  =====================*/
00514 static void pfsNodeConstrNormal( int ref_id, PfsElem *elem, PFSGeoPoint *normal )
00515 {
00516  PfsNode    *node;               /* pointer to given reference node */
00517  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
00518  double     size;                /* normal vector size */
00519 
00520 /* Get the pointer to the reference node.
00521  */
00522  node = &pfs->nodelist[ref_id];
00523 
00524 /* Initialize the normal vector as the normal of the given 
00525  * element or as null vector if the given element is null.
00526  */
00527  if( elem == NULL )
00528  {
00529   normal->x = 0.0;
00530   normal->y = 0.0;
00531   normal->z = 0.0;
00532  }
00533  else
00534  {
00535   *normal = elem->normal;
00536  }
00537 
00538 /* Compute the average normal construction vector.
00539  */
00540  for( adjnode = node->adj_head;
00541       adjnode != NULL;
00542       adjnode = adjnode->next )
00543  {
00544   if( adjnode->elem != NULL )
00545   {
00546    normal->x += adjnode->elem->normal.x;
00547    normal->y += adjnode->elem->normal.y;
00548    normal->z += adjnode->elem->normal.z;
00549   }
00550  }
00551 
00552  size = PFSGeoVecLen( normal );
00553  if( size > 0.0 )
00554  {
00555   normal->x /= size;
00556   normal->y /= size;
00557   normal->z /= size;
00558  }
00559 }
00560 
00561 /*========================  pfsAddAdjNode  ========================*/
00606 static int  pfsAddAdjNode( int ref_id, int adj_id, PfsElem* elem )
00607 {
00608  PfsNode    *node;               /* pointer to given reference node */
00609  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
00610  PfsAdjNode *newadj;             /* new adjacent node created */
00611  PfsNode    *first_adjnode;      /* first adjacent node of ref. node */
00612  PfsAdjNode *prevadjnode;        /* pointer to previous adjacent node */
00613  double     cur_angle;           /* current adj.node angle around ref. node */
00614  double     new_angle;           /* new adj. node angle around ref. node */
00615  PFSGeoLine    nline;               /* normal line at reference point */
00616 
00617 /* Get the pointer to the reference node.
00618  */
00619  node = &pfs->nodelist[ref_id];
00620 
00621 /* Check to see whether the given node (given by its id) is already
00622  * in the list of adjacent nodes of the reference node.
00623  */
00624  for( adjnode = node->adj_head;
00625       adjnode != NULL;
00626       adjnode = adjnode->next )
00627  {
00628   if( adjnode->id == adj_id )
00629   {
00630 /* If the given adjancent node was already in the list, 
00631  * check for more than two elements using a pair of nodes and
00632  * for reversed element incidence order.
00633  */
00634    if( adjnode->refcnt == 2 )
00635    {
00636     printf( "\n Found more than two elements framing into an edge!\n"
00637             " Ref. node: %d, Adj. node: %d, Adj. elem.:%p \n", 
00638             ref_id, adj_id, elem  );
00639     return( PFS_NON_MANIFOLD_EDGE );
00640    }
00641    if( adjnode->elem == NULL )
00642    {
00643     if( elem == NULL )
00644     {
00645      printf( "\n Found reversed element incidence order!\n"
00646              " Ref. node: %d, Adj. node: %d, Adj. elem.:%p \n", 
00647              ref_id, adj_id, elem  );
00648      return( PFS_INVERSE_INCIDENCE );
00649     }
00650     else
00651     {
00652      adjnode->elem = elem;
00653     }
00654    }
00655    else
00656    {
00657     if( elem != NULL )
00658     {
00659      printf( "\n Found reversed element incidence order!\n"
00660              " Ref. node: %d, Adj. node: %d, Adj. elem.:%p \n", 
00661              ref_id, adj_id, elem  );
00662      return( PFS_INVERSE_INCIDENCE );
00663     }
00664    }
00665 
00666 /* If no problem is found, just increment its reference counter
00667  * and updates the index of the adjacent element.
00668  */
00669    adjnode->refcnt++;
00670    return( PFS_SUCCESS );
00671   }
00672  }
00673 
00674 /* Update the number of adjacent nodes of the reference node.
00675  */
00676  node->degree += 1;
00677 
00678 /* Get memory of new adjacent node and initialize it.
00679  */
00680  newadj = (PfsAdjNode *)malloc( sizeof( PfsAdjNode ) );
00681  newadj->id = adj_id;
00682  newadj->elem = elem;
00683  newadj->refcnt = 1;
00684  newadj->AtA[0][0] = 0.0;
00685  newadj->AtA[0][1] = 0.0;
00686  newadj->AtA[1][0] = 0.0;
00687  newadj->AtA[1][1] = 0.0;
00688 
00689 /* For a new adjacent node, check to see whether the 
00690  * list is empty.  If that is the case, just 
00691  * initialize the list with the new adjacent node.
00692  * Otherwise, put it in the list ordering the adjacent
00693  * node in counter-clockwise order radially around the 
00694  * reference node, starting from the first adjacent node.
00695  * In this case, build a node construction normal based on
00696  * the given element normal (if the element is not null) and
00697  * on the normal vectors of the adjacent elements in the list
00698  * of adjacent nodes.
00699  */
00700  if( node->adj_head == NULL )
00701  {
00702   newadj->next = node->adj_head;
00703   node->adj_head = newadj;
00704  }
00705  else
00706  {
00707   first_adjnode = &pfs->nodelist[node->adj_head->id];
00708   nline.d = node->coord;
00709   pfsNodeConstrNormal( ref_id, elem, &nline.e );
00710   new_angle = PFSGeoAngPtAboutLine( &nline, 
00711                                  &pfs->nodelist[adj_id].coord, 
00712                                  &first_adjnode->coord );
00713   prevadjnode = node->adj_head;
00714   cur_angle = 0.0;
00715   adjnode = prevadjnode->next;
00716   while( adjnode != NULL )
00717   {
00718    cur_angle = PFSGeoAngPtAboutLine( &nline, 
00719                                   &pfs->nodelist[adjnode->id].coord, 
00720                                   &first_adjnode->coord );
00721    if( new_angle < cur_angle )
00722     break;
00723    prevadjnode = adjnode;
00724    adjnode = prevadjnode->next;
00725   }
00726   newadj->next = prevadjnode->next;
00727   prevadjnode->next = newadj;
00728  }
00729  return( PFS_SUCCESS );
00730 }
00731 
00732 /*=======================  pfsBuildNodeAdj  =======================*/
00756 static int pfsBuildNodeAdj( void )
00757 {
00758  int       node;                  /* current element node id     */
00759  int       prev;                  /* previous node on elem. bdry */
00760  int       next;                  /* next node on element boudry */
00761  int       j;                     /* counter                     */
00762  int       status;
00763 
00764  double xmin, xmax;
00765  double ymin, ymax;
00766  double zmin, zmax;
00767 
00768  void* e = NULL;
00769 
00770 /* Traverse the list of elements in mesh.
00771  */
00772  PFSRtreeInitTraverse( pfs->elm3d_tree );
00773 
00774  while( (e = PFSRtreeTraverse( pfs->elm3d_tree,
00775                                &xmin, &xmax, 
00776                                &ymin, &ymax,
00777                                &zmin, &zmax )) != NULL )
00778  {
00779    PfsElem* elem = (PfsElem *)e;
00780 
00781 /* Traverse the nodes of current element.
00782  */
00783   for( j = 0; j < 3; j++ )
00784   {
00785 /* Get current, previous and next node on element boundary.
00786  */
00787    node = elem->inc[(j+1)%3];
00788    prev = elem->inc[j];
00789    next = elem->inc[(j+2)%3];
00790 
00791 /* Add previous and next nodes to the linked list of adjacent
00792  * nodes of current node, or just increment their reference 
00793  * counters.
00794  * Set current element as adjacent element of current node 
00795  * only for next node.  By doing this, this element will
00796  * appear only once as an adjacent element of this node.
00797  */
00798    status = pfsAddAdjNode( node, prev, NULL );
00799    if( status != PFS_SUCCESS )
00800     return( status );
00801    status = pfsAddAdjNode( node, next, elem );
00802    if( status != PFS_SUCCESS )
00803     return( status );
00804   }
00805  }
00806  return( PFS_SUCCESS );
00807 }
00808 
00809 /*=======================  pfsChkBdryNode  ========================*/
00821 static int pfsChkBdryNode( int id )
00822 {
00823  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
00824 
00825  for( adjnode = pfs->nodelist[id].adj_head;
00826       adjnode != NULL;
00827       adjnode = adjnode->next )
00828  {
00829   if( adjnode->refcnt != 2 )
00830   {
00831    return( 1 );
00832   }
00833  }
00834  return( 0 );
00835 }
00836 
00837 /*======================  pfsClassifyNodes  =======================*/
00842 static void pfsClassifyNodes( void )
00843 {
00844  int        id;                    /* current node index           */
00845 
00846  for( id = 0; id < pfs->numnodes; id++ )
00847  {
00848   if( pfsChkBdryNode( id ) )
00849    pfs->nodelist[id].type = NODE_BOUNDARY;
00850   else
00851    pfs->nodelist[id].type = NODE_INTERIOR;
00852  }
00853 }
00854 
00855 /*=====================  pfsOrderBdryNodeAdj  =====================*/
00873 static int pfsOrderBdryNodeAdj( int ref_id )
00874 {
00875  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
00876  PfsAdjNode *curlast = NULL;     /* pointer to current last adj. node in list */
00877  PfsAdjNode *adjlast = NULL;     /* pointer to target last adj. node in list */
00878 
00879  for( adjnode = pfs->nodelist[ref_id].adj_head;
00880       adjnode != NULL;
00881       adjnode = adjnode->next )
00882  {
00883   if( adjnode->elem == NULL )
00884   {
00885    if( adjlast != NULL )
00886    {
00887     printf( "\n Found inconsistent boundary neighborhood!\n"
00888             " Ref. boundary node: %d\n", ref_id );
00889     return( PFS_NON_MANIFOLD_VERTEX );
00890    }
00891    else
00892    {
00893     adjlast = adjnode;
00894    }
00895   }
00896   if( adjnode->next == NULL )
00897    curlast = adjnode;
00898  }
00899 
00900 /* If the given node is really a boundary node, there should be
00901  * an adjacent node with a field elem = NULL.  If no one is found
00902  * something wrong is going one.  In this case (which is really
00903  * a bug), send a message of bad adjacency neighborhood and return
00904  * an invalid status.
00905  */
00906  if( adjlast == NULL )
00907  {
00908   printf( "\n Found inconsistent boundary neighborhood!\n"
00909           " Ref. boundary node: %d\n", ref_id );
00910   return( PFS_NON_MANIFOLD_VERTEX );
00911  }
00912 
00913 /* If target last adjacent node is already the last one,
00914  * there is nothing to do.  Just return a valid status.
00915  */
00916  if( adjlast == curlast )
00917   return( PFS_SUCCESS );
00918 
00919 /* In the cannonical case, make the current last node precede 
00920  * the current head of list, and make next adjacent node be 
00921  * the new head of the list.  This will also consider the case
00922  * in which the target last adjacent node is the current 
00923  * head of the list.
00924  */
00925  curlast->next = pfs->nodelist[ref_id].adj_head;
00926  pfs->nodelist[ref_id].adj_head = adjlast->next;
00927  adjlast->next = NULL;
00928  
00929  return( PFS_SUCCESS );
00930 }
00931 
00932 /*===================  pfsOrderAllBdryNodeAdj  ====================*/
00946 static int pfsOrderAllBdryNodeAdj( void )
00947 {
00948  int       id;
00949  int       status;
00950 
00951  if( pfs->nodelist != NULL )
00952  {
00953   for( id = 0; id < pfs->numnodes; id++ )
00954   {
00955    if( pfs->nodelist[id].type != NODE_INTERIOR )
00956    {
00957     status = pfsOrderBdryNodeAdj( id );
00958     if( status != PFS_SUCCESS )
00959      return( status );
00960    }
00961   }
00962  }
00963  return( PFS_SUCCESS );
00964 }
00965 
00966 /*======================  pfsMarkBdryNodes  =======================*/
00971 static void pfsMarkBdryNodes( void )
00972 {
00973  int       id;
00974 
00975  if( pfs->nodelist != NULL )
00976  {
00977   for( id = 0; id < pfs->numnodes; id++ )
00978   {
00979    if( pfs->nodelist[id].type == NODE_BOUNDARY )
00980    {
00981     pfs->nodelist[id].type = NODE_MARKED;
00982    }
00983   }
00984  }
00985 }
00986 
00987 /*=====================  pfsUnmarkLoopNodes  ======================*/
01002 static void pfsUnmarkLoopNodes( int ref_id )
01003 {
01004  PfsNode    *ref_node;           /* pointer to given reference node */
01005  PfsNode    *node;               /* pointer to current node on loop */
01006 
01007  if( pfs->nodelist[ref_id].type != NODE_MARKED )
01008   return;
01009 
01010  ref_node = node = &pfs->nodelist[ref_id];
01011 
01012  do
01013  {
01014   node->type = NODE_BOUNDARY;
01015   node = &pfs->nodelist[node->adj_head->id];
01016  } while( node != ref_node );
01017 }
01018 
01019 /*======================  pfsBuildLoopList  =======================*/
01036 static void pfsBuildLoopList( void )
01037 {
01038  int       *looplist;   /* auxiliar loop list (stores first node) */
01039  int       found_loop;  /* flag for found next loop */
01040  int       id;          /* node id */
01041  int       j;           /* loop counter */
01042 
01043  pfs->numloops = 0;
01044 
01045  if( pfs->nodelist == NULL )
01046   return;
01047 
01048  if( pfs->numnodes == 0 )
01049   return;
01050 
01051  if( pfs->numelems == 0 )
01052   return;
01053 
01054  if( pfs->looplist != NULL )
01055   free( pfs->looplist );
01056 
01057  looplist = (int *)calloc( pfs->numnodes, sizeof( int ) );
01058 
01059  pfsMarkBdryNodes( );
01060 
01061  do
01062  {
01063   found_loop = 0;
01064   for( id = 0; id < pfs->numnodes; id++ )
01065   {
01066    if( pfs->nodelist[id].type == NODE_MARKED )
01067    {
01068     found_loop = 1;
01069     looplist[pfs->numloops++] = id;
01070     pfsUnmarkLoopNodes( id );
01071     break;
01072    }
01073   }
01074  } while( found_loop );
01075 
01076  pfs->looplist = (int *)calloc( pfs->numloops, sizeof( int ) );
01077  for( j = 0; j < pfs->numloops; j++ )
01078  {
01079   pfs->looplist[j] = looplist[j];
01080  }
01081 
01082  free( looplist );
01083 }
01084 
01085 /*=======================  pfsDelNodeList  ========================*/
01090 static void pfsDelNodeList( PfsSurf *surf )
01091 {
01092  PfsAdjNode *adjnode;    /* auxiliar adjacent node pointer   */
01093  int        i;           /* counter                          */
01094 
01095  if( surf->nodelist != NULL )
01096  {
01097   for( i = 0; i < surf->numnodes; i++ )
01098   {
01099    while( surf->nodelist[i].adj_head )
01100    {
01101     adjnode = surf->nodelist[i].adj_head;
01102     surf->nodelist[i].adj_head = adjnode->next;
01103     free( adjnode );
01104    }
01105   }
01106   free( surf->nodelist );
01107  }
01108  surf->nodelist = NULL;
01109 }
01110 
01111 /*=======================  pfsDelElemList  ========================*/
01116 static void pfsDelElemList( PfsSurf *surf )
01117 {
01118  double xmin, ymin, zmin;
01119  double xmax, ymax, zmax;
01120  void   *e = NULL;
01121 
01122  if( surf->elm2d_tree != NULL )
01123  {
01124   PFSRtreeDestroy( surf->elm2d_tree );
01125  }
01126 
01127  if( surf->elm3d_tree != NULL )
01128  {
01129   PFSRtreeInitTraverse( surf->elm3d_tree );
01130 
01131   while( (e = PFSRtreeTraverse( surf->elm3d_tree,
01132                                 &xmin, &xmax, 
01133                                 &ymin, &ymax,
01134                                 &zmin, &zmax )) != NULL )
01135   {
01136    PfsElem* curr_elem = (PfsElem *)e;
01137    free( curr_elem );
01138   }
01139 
01140   PFSRtreeDestroy( surf->elm3d_tree );
01141  }
01142 
01143  surf->elm2d_tree = NULL;
01144  surf->elm3d_tree = NULL;
01145 }
01146 
01147 /*======================  pfsGetEdgeAdjElems  =====================*/
01157 static int pfsGetEdgeAdjElems( int ni, int nj,
01158                                PfsElem **e_left, PfsElem **e_right )
01159 {
01160  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
01161  int        found_node;
01162 
01163  found_node = 0;
01164  for( adjnode = pfs->nodelist[ni].adj_head;
01165       adjnode != NULL;
01166       adjnode = adjnode->next )
01167  {
01168   if( adjnode->id == nj )
01169   {
01170    *e_left = adjnode->elem;
01171    found_node = 1;
01172    break;
01173   }
01174  }
01175 
01176  if( !found_node )
01177   return( 0 );
01178 
01179  found_node = 0;
01180  for( adjnode = pfs->nodelist[nj].adj_head;
01181       adjnode != NULL;
01182       adjnode = adjnode->next )
01183  {
01184   if( adjnode->id == ni )
01185   {
01186    *e_right = adjnode->elem;
01187    found_node = 1;
01188    return( 1 );
01189   }
01190  }
01191 
01192  return( 0 );
01193 }
01194 
01195 /*=====================  pfsCompute3dBoundBox  ====================*/
01199 static void pfsCompute3dBoundBox( void )
01200 {
01201  int       i;                              /* counter   */
01202 
01203  if( pfs->numnodes < 1 )
01204   return;
01205 
01206  pfs->box_xmin = pfs->box_xmax = pfs->nodelist[0].coord.x;
01207  pfs->box_ymin = pfs->box_ymax = pfs->nodelist[0].coord.y;
01208  pfs->box_zmin = pfs->box_zmax = pfs->nodelist[0].coord.z;
01209 
01210  for( i = 1; i < pfs->numnodes; i++ )
01211  {
01212   if( pfs->box_xmin > pfs->nodelist[i].coord.x ) 
01213    pfs->box_xmin = pfs->nodelist[i].coord.x;
01214   if( pfs->box_xmax < pfs->nodelist[i].coord.x ) 
01215    pfs->box_xmax = pfs->nodelist[i].coord.x;
01216   if( pfs->box_ymin > pfs->nodelist[i].coord.y ) 
01217    pfs->box_ymin = pfs->nodelist[i].coord.y;
01218   if( pfs->box_ymax < pfs->nodelist[i].coord.y ) 
01219    pfs->box_ymax = pfs->nodelist[i].coord.y;
01220   if( pfs->box_zmin > pfs->nodelist[i].coord.z ) 
01221    pfs->box_zmin = pfs->nodelist[i].coord.z;
01222   if( pfs->box_zmax < pfs->nodelist[i].coord.z ) 
01223    pfs->box_zmax = pfs->nodelist[i].coord.z;
01224  }
01225 }
01226 
01227 /*=========================  pfsElemNormal  =======================*/
01236 static void pfsElemNormal( PfsElem *elem )
01237 {
01238  int      i, first, curr, prev;
01239  double   size;
01240 
01241  elem->normal.x = 0.0;
01242  elem->normal.y = 0.0;
01243  elem->normal.z = 0.0;
01244 
01245  first = elem->inc[0];
01246 
01247  for( i = 2; i < 3; i++ )
01248  {
01249   curr = elem->inc[i];
01250   prev = elem->inc[i-1];
01251 
01252   elem->normal.x +=
01253         (pfs->nodelist[prev].coord.y - pfs->nodelist[first].coord.y) *
01254         (pfs->nodelist[curr].coord.z - pfs->nodelist[first].coord.z) -
01255         (pfs->nodelist[prev].coord.z - pfs->nodelist[first].coord.z) *
01256         (pfs->nodelist[curr].coord.y - pfs->nodelist[first].coord.y);
01257   elem->normal.y +=
01258        -(pfs->nodelist[prev].coord.x - pfs->nodelist[first].coord.x) *
01259         (pfs->nodelist[curr].coord.z - pfs->nodelist[first].coord.z) +
01260         (pfs->nodelist[prev].coord.z - pfs->nodelist[first].coord.z) *
01261         (pfs->nodelist[curr].coord.x - pfs->nodelist[first].coord.x);
01262   elem->normal.z +=
01263         (pfs->nodelist[prev].coord.x - pfs->nodelist[first].coord.x) *
01264         (pfs->nodelist[curr].coord.y - pfs->nodelist[first].coord.y) -
01265         (pfs->nodelist[prev].coord.y - pfs->nodelist[first].coord.y) *
01266         (pfs->nodelist[curr].coord.x - pfs->nodelist[first].coord.x);
01267  }
01268 
01269  size = PFSGeoVecLen( &elem->normal );
01270 
01271  if( size > 0.0 )
01272  {
01273   elem->normal.x /= size;
01274   elem->normal.y /= size;
01275   elem->normal.z /= size;
01276   elem->area = size * 0.5;
01277  }
01278 }
01279 
01280 /*=========================  pfsElemCenter  ========================*/
01286 static void pfsElemCenter( PfsElem *elem )
01287 {
01288  int node;
01289  int i;
01290 
01291  elem->center.x = 0.0;
01292  elem->center.y = 0.0;
01293  elem->center.z = 0.0;
01294 
01295  for( i = 0; i < 3; i++ )
01296  {
01297   node = elem->inc[i];
01298   elem->center.x += pfs->nodelist[node].coord.x;
01299   elem->center.y += pfs->nodelist[node].coord.y;
01300   elem->center.z += pfs->nodelist[node].coord.z;
01301  }
01302 
01303  elem->center.x /= 3.0;
01304  elem->center.y /= 3.0;
01305  elem->center.z /= 3.0;
01306 }
01307 
01308 /*====================  pfsElemLocalGradients  ====================*/
01319 static void pfsElemLocalGradients( PfsElem *elem )
01320 {
01321  int    v0;
01322  int    v1;
01323  int    v2;
01324  double r0;
01325  double r1;
01326  double r2;
01327  double r00;
01328  double r11;
01329  double r22;
01330  double x1;
01331  double x2;
01332  double y2;
01333  double sqrt_dt;
01334 
01335  v0 = elem->inc[0];
01336  v1 = elem->inc[1];
01337  v2 = elem->inc[2];
01338 
01339  r0 = Len3( pfs->nodelist[v0].coord.x - pfs->nodelist[v2].coord.x, 
01340             pfs->nodelist[v0].coord.y - pfs->nodelist[v2].coord.y, 
01341             pfs->nodelist[v0].coord.z - pfs->nodelist[v2].coord.z );
01342  r1 = Len3( pfs->nodelist[v2].coord.x - pfs->nodelist[v1].coord.x, 
01343             pfs->nodelist[v2].coord.y - pfs->nodelist[v1].coord.y, 
01344             pfs->nodelist[v2].coord.z - pfs->nodelist[v1].coord.z );
01345  r2 = Len3( pfs->nodelist[v1].coord.x - pfs->nodelist[v0].coord.x, 
01346             pfs->nodelist[v1].coord.y - pfs->nodelist[v0].coord.y, 
01347             pfs->nodelist[v1].coord.z - pfs->nodelist[v0].coord.z );
01348  r00 = r0*r0;
01349  r11 = r1*r1;
01350  r22 = r2*r2;
01351 
01352 /* x0 = 0.0;
01353    y0 = 0.0; */
01354    x1 = r2;
01355 /* y1 = 0.0; */
01356    x2 = 0.5 * (r22 + r00 - r11) / r2;
01357    y2 = 0.5 * sqrt(2.0*(r00*r22 + r22*r11 + r00*r11) -
01358                         r00*r00 - r11*r11 - r22*r22) / r2;
01359 
01360 /* dt = (x0*y1 - y0*x1) + (x1*y2 - y1*x2) + (x2*y0 - y2*x0)
01361  */
01362  sqrt_dt = sqrt( x1*y2 );
01363 
01364 /* [W]*sqrt_dt = |(x2-x1)   (y2-y1)|
01365  *               |(x0-x2)   (y0-y2)|
01366  *               |(x1-x0)   (y1-y0)|
01367  */
01368 
01369  elem->W[0][0] = (x2-x1) / sqrt_dt;
01370  elem->W[0][1] =  y2     / sqrt_dt;
01371  elem->W[1][0] = -x2     / sqrt_dt;
01372  elem->W[1][1] = -y2     / sqrt_dt;
01373  elem->W[2][0] =  x1     / sqrt_dt;
01374  elem->W[2][1] =  0.0;
01375 }
01376 
01377 /*=======================  pfsElem3dBoundBox  ========================*/
01383 static void pfsElem3dBoundBox( PfsElem *elem )
01384 {
01385  int    node;
01386  int    i;
01387 
01388  node = elem->inc[0];
01389 
01390  elem->min3dbox.x =
01391  elem->max3dbox.x = pfs->nodelist[node].coord.x;
01392  elem->min3dbox.y =
01393  elem->max3dbox.y = pfs->nodelist[node].coord.y;
01394  elem->min3dbox.z =
01395  elem->max3dbox.z = pfs->nodelist[node].coord.z;
01396 
01397  for( i = 1; i < 3; i++ )
01398  {
01399   node = elem->inc[i];
01400 
01401   if( pfs->nodelist[node].coord.x < elem->min3dbox.x )
01402       elem->min3dbox.x = pfs->nodelist[node].coord.x;
01403 
01404   if( pfs->nodelist[node].coord.y < elem->min3dbox.y )
01405       elem->min3dbox.y = pfs->nodelist[node].coord.y;
01406 
01407   if( pfs->nodelist[node].coord.z < elem->min3dbox.z )
01408       elem->min3dbox.z = pfs->nodelist[node].coord.z;
01409 
01410   if( pfs->nodelist[node].coord.x > elem->max3dbox.x )
01411       elem->max3dbox.x = pfs->nodelist[node].coord.x;
01412 
01413   if( pfs->nodelist[node].coord.y > elem->max3dbox.y )
01414       elem->max3dbox.y = pfs->nodelist[node].coord.y;
01415 
01416   if( pfs->nodelist[node].coord.z > elem->max3dbox.z )
01417       elem->max3dbox.z = pfs->nodelist[node].coord.z;
01418  }
01419 
01420  PFSRtreeInsert( pfs->elm3d_tree, (void *)elem, elem->min3dbox.x,
01421                                                 elem->max3dbox.x,
01422                                                 elem->min3dbox.y,
01423                                                 elem->max3dbox.y,
01424                                                 elem->min3dbox.z,
01425                                                 elem->max3dbox.z );
01426 }
01427 
01428 /*=========================  pfsNodeNormal  =======================*/
01434 static void pfsNodeNormal( int id )
01435 {
01436  PfsNode    *node;               /* pointer to reference node */
01437  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
01438  PfsElem    *elem;               /* index of an adjacent element */
01439  double     size;                /* normal vector size */
01440 
01441  node = &pfs->nodelist[id];
01442 
01443  node->normal.x = 0.0;
01444  node->normal.y = 0.0;
01445  node->normal.z = 0.0;
01446 
01447  for( adjnode = node->adj_head; adjnode != NULL; adjnode = adjnode->next )
01448  {
01449   elem = adjnode->elem;
01450   if( elem != NULL )
01451   {
01452    node->normal.x += elem->normal.x;
01453    node->normal.y += elem->normal.y;
01454    node->normal.z += elem->normal.z;
01455   }
01456  }
01457 
01458  size = PFSGeoVecLen( &node->normal );
01459  if( size > 0.0 )
01460  {
01461   node->normal.x /= size;
01462   node->normal.y /= size;
01463   node->normal.z /= size;
01464  }
01465 }
01466 
01467 /*========================  pfsNodeNormals  =======================*/
01473 static void pfsNodeNormals( void )
01474 {
01475  int       i;
01476 
01477  if( pfs->nodelist != NULL )
01478  {
01479   for( i = 0; i < pfs->numnodes; i++ )
01480   {
01481    pfsNodeNormal( i );
01482   }
01483  }
01484 }
01485 
01486 /*========================  pfsFindRefElem  =======================*/
01505 static void pfsFindRefElem( void )
01506 {
01507  double   xmin, ymin, zmin;
01508  double   xmax, ymax, zmax;
01509  PfsElem  *elem;
01510  void     *e = NULL;
01511  double   area_avrg = 0.0;
01512  PFSGeoPoint normal_avrg;
01513  double   size;
01514  double   dotprod;
01515  double   max_dotprod = 0.0;
01516 
01517  pfs->ref_elem = NULL;
01518  pfs->ref_node = -1;
01519 
01520  if( pfs->elm3d_tree == NULL )
01521   return;
01522 
01523  normal_avrg.x = 0.0;
01524  normal_avrg.y = 0.0;
01525  normal_avrg.z = 0.0;
01526 
01527  PFSRtreeInitTraverse( pfs->elm3d_tree );
01528  while( (e = PFSRtreeTraverse( pfs->elm3d_tree,
01529                                &xmin, &xmax, 
01530                                &ymin, &ymax,
01531                                &zmin, &zmax )) != NULL )
01532  {
01533   elem = (PfsElem *)e;
01534   area_avrg += elem->area;
01535   normal_avrg.x += elem->area * elem->normal.x;
01536   normal_avrg.y += elem->area * elem->normal.y;
01537   normal_avrg.z += elem->area * elem->normal.z;
01538  }
01539 
01540  size = PFSGeoVecLen( &normal_avrg );
01541 
01542  if( size > 0.0 )
01543  {
01544   normal_avrg.x /= size;
01545   normal_avrg.y /= size;
01546   normal_avrg.z /= size;
01547  }
01548  else
01549  {
01550   return;
01551  }
01552 
01553  area_avrg /= (double)pfs->numelems;
01554 
01555  PFSRtreeInitTraverse( pfs->elm3d_tree );
01556  while( (e = PFSRtreeTraverse( pfs->elm3d_tree,
01557                                &xmin, &xmax, 
01558                                &ymin, &ymax,
01559                                &zmin, &zmax )) != NULL )
01560  {
01561   elem = (PfsElem *)e;
01562   if( elem->area > area_avrg*0.5 )
01563   {
01564    dotprod = PFSGeoDotProd( &elem->normal, &normal_avrg );
01565    if( dotprod > max_dotprod )
01566    {
01567     max_dotprod = dotprod;
01568     pfs->ref_elem = elem;
01569    }
01570   }
01571  }
01572 
01573  if( pfs->ref_elem != NULL )
01574  {
01575   pfs->ref_node = elem->inc[0];
01576   pfs->iter_toler = ITER_TOLER * Len3(
01577    pfs->nodelist[elem->inc[1]].coord.x - pfs->nodelist[pfs->ref_node].coord.x, 
01578    pfs->nodelist[elem->inc[1]].coord.y - pfs->nodelist[pfs->ref_node].coord.y, 
01579    pfs->nodelist[elem->inc[1]].coord.z - pfs->nodelist[pfs->ref_node].coord.z );
01580  }
01581 }
01582 
01583 /*=====================  pfsNodeConfMapCoeff  =====================*/
01595 static void pfsNodeConfMapCoeff( int ref_id )
01596 {
01597  PfsNode    *node;               /* pointer to reference node */
01598  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
01599  PfsElem    *e_prev;             /* CCW previous adjacent element */
01600  PfsElem    *e_next;             /* CCW next adjacent element */
01601  int        adj_id;              /* id of adjacent node */
01602  int        ref_previd = 0;      /* local id of ref. node in previous elem. */
01603  int        adj_previd = 0;      /* local id of adj. node in previous elem. */
01604  int        ref_nextid = 0;      /* local id of ref. node in next elem. */
01605  int        adj_nextid = 0;      /* local id of adj. node in next elem. */
01606  int        j;
01607 
01608  node = &pfs->nodelist[ref_id];
01609 
01610 /* Reset the coefficient values.
01611  */
01612  node->AtA[0][0] = 0.0;
01613  node->AtA[0][1] = 0.0;
01614  node->AtA[1][0] = 0.0;
01615  node->AtA[1][1] = 0.0;
01616 
01617 /* Get the last adjacent node in counter-clockwise order.
01618  * The adjacent element of the last adjacent node (if it exists) is 
01619  * the previous element of the first adjacent node.
01620  * It might be null if the reference node is a boundary node.
01621  */
01622  for( adjnode = node->adj_head; adjnode->next != NULL; adjnode = adjnode->next )
01623  ;
01624  e_next = adjnode->elem;
01625 
01626 /* Traverse the adjacent nodes and elements in counter-clockwise order
01627  * around reference node and add the contributions of the previous
01628  * and next adjacent elements to the coefficients of the reference node
01629  * and of each adjacent node.
01630  */
01631  for( adjnode = node->adj_head; adjnode != NULL; adjnode = adjnode->next )
01632  {
01633   adjnode->AtA[0][0] = 0.0;
01634   adjnode->AtA[0][1] = 0.0;
01635   adjnode->AtA[1][0] = 0.0;
01636   adjnode->AtA[1][1] = 0.0;
01637   e_prev = e_next;
01638   e_next = adjnode->elem;
01639   adj_id = adjnode->id;
01640 
01641 /* Find the position of reference and adjacent nodes in both
01642  * previous and next adjacent elements.
01643  */
01644   for( j = 0; j < 3; j++ )
01645   {
01646    if( e_prev != NULL )
01647    {
01648     if( e_prev->inc[j] == ref_id )
01649      ref_previd = j;
01650     if( e_prev->inc[j] == adj_id )
01651      adj_previd = j;
01652    }
01653    if( e_next != NULL )
01654    {
01655     if( e_next->inc[j] == ref_id )
01656      ref_nextid = j;
01657     if( e_next->inc[j] == adj_id )
01658      adj_nextid = j;
01659    }
01660   }
01661 
01662 /* Add the contribution of the next element (if it exists) to the 
01663  * coefficients of the reference node.
01664  */
01665   if( e_next != NULL )
01666   {
01667    node->AtA[0][0] += e_next->W[ref_nextid][0] * e_next->W[ref_nextid][0] +
01668                       e_next->W[ref_nextid][1] * e_next->W[ref_nextid][1];
01669    node->AtA[0][1] += e_next->W[ref_nextid][0] * e_next->W[ref_nextid][1] -
01670                       e_next->W[ref_nextid][1] * e_next->W[ref_nextid][0];
01671    node->AtA[1][0] += e_next->W[ref_nextid][1] * e_next->W[ref_nextid][0] -
01672                       e_next->W[ref_nextid][0] * e_next->W[ref_nextid][1];
01673    node->AtA[1][1] += e_next->W[ref_nextid][1] * e_next->W[ref_nextid][1] +
01674                       e_next->W[ref_nextid][0] * e_next->W[ref_nextid][0];
01675   }
01676 
01677 /* Add the contribution of the previous and next elements (if 
01678  * they exist) to the coefficients of the adjacent node.
01679  */
01680   if( e_prev != NULL )
01681   {
01682    adjnode->AtA[0][0] += e_prev->W[adj_previd][0] * e_prev->W[ref_previd][0] +
01683                          e_prev->W[adj_previd][1] * e_prev->W[ref_previd][1];
01684    adjnode->AtA[0][1] += e_prev->W[adj_previd][0] * e_prev->W[ref_previd][1] -
01685                          e_prev->W[adj_previd][1] * e_prev->W[ref_previd][0];
01686    adjnode->AtA[1][0] += e_prev->W[adj_previd][1] * e_prev->W[ref_previd][0] -
01687                          e_prev->W[adj_previd][0] * e_prev->W[ref_previd][1];
01688    adjnode->AtA[1][1] += e_prev->W[adj_previd][1] * e_prev->W[ref_previd][1] +
01689                          e_prev->W[adj_previd][0] * e_prev->W[ref_previd][0];
01690   }
01691 
01692   if( e_next != NULL )
01693   {
01694    adjnode->AtA[0][0] += e_next->W[adj_nextid][0] * e_next->W[ref_nextid][0] +
01695                          e_next->W[adj_nextid][1] * e_next->W[ref_nextid][1];
01696    adjnode->AtA[0][1] += e_next->W[adj_nextid][0] * e_next->W[ref_nextid][1] -
01697                          e_next->W[adj_nextid][1] * e_next->W[ref_nextid][0];
01698    adjnode->AtA[1][0] += e_next->W[adj_nextid][1] * e_next->W[ref_nextid][0] -
01699                          e_next->W[adj_nextid][0] * e_next->W[ref_nextid][1];
01700    adjnode->AtA[1][1] += e_next->W[adj_nextid][1] * e_next->W[ref_nextid][1] +
01701                          e_next->W[adj_nextid][0] * e_next->W[ref_nextid][0];
01702   }
01703  }
01704 }
01705 
01706 /*===================  pfsConfMapCoefficients  ====================*/
01713 static void pfsConfMapCoefficients( void )
01714 {
01715  int       i;
01716 
01717  if( pfs->ref_elem == NULL )
01718   return;
01719 
01720  if( pfs->nodelist != NULL )
01721  {
01722   for( i = 0; i < pfs->numnodes; i++ )
01723   {
01724    pfsNodeConfMapCoeff( i );
01725   }
01726  }
01727 }
01728 
01729 /*========================  pfsInitParams  ========================*/
01744 static void pfsInitParams( void )
01745 {
01746  PFSGeoNormPlane refplane;         /* plane that contains reference element */
01747  PfsNode      *refnode;         /* pointer to reference node */
01748  PfsNode      *node;            /* pointer to current node */
01749  int          nodeid;           /* index of a node */
01750  PFSGeoPoint     proj_pt;          /* proj. of node on plane */
01751  PFSGeoPoint     x_axis = { 1.0, 0.0, 0.0 };
01752  PFSGeoPoint     y_axis = { 0.0, 1.0, 0.0 };
01753  PFSGeoPoint     z_axis = { 0.0, 0.0, 1.0 };
01754 
01755  if( !pfs )
01756   return;
01757 
01758  refnode = &pfs->nodelist[pfs->ref_node];
01759 
01760 /* Make the normal to the reference plane be the normal of the ref. elem.
01761  */
01762  refplane.n.x = pfs->ref_elem->normal.x;
01763  refplane.n.y = pfs->ref_elem->normal.y;
01764  refplane.n.z = pfs->ref_elem->normal.z;
01765 
01766 /* Make the origin of parametric plane space be the first ref. point.
01767  */
01768  refplane.a.x = refnode->coord.x;
01769  refplane.a.y = refnode->coord.y;
01770  refplane.a.z = refnode->coord.z;
01771 
01772 /* Try to lay the first plane parametric vector be at the projection
01773  * of the major x-axis with the plane.  If the x-axis is almost (less
01774  * then 30 degrees) parallel to the plane normal vector, try to do 
01775  * the same with the y-axis and z-axis (in this order).
01776  */
01777  PFSGeoCrossProd( &refplane.n, &x_axis, &refplane.v );
01778  if( ABS( PFSGeoVecLen( &refplane.v ) ) < 0.5 )
01779  {
01780   PFSGeoCrossProd( &refplane.n, &y_axis, &refplane.v );
01781   if( ABS( PFSGeoVecLen( &refplane.v ) ) < 0.5 )
01782   {
01783    PFSGeoCrossProd( &refplane.n, &z_axis, &refplane.v );
01784   }
01785  }
01786  PFSGeoVecNormalize( &refplane.v, &refplane.v );
01787  PFSGeoCrossProd( &refplane.v, &refplane.n, &refplane.u );
01788 
01789 /* Compute the initial parametric coordinates of all nodes 
01790  * from the projection of their points on the reference plane.
01791  */
01792  for( nodeid = 0; nodeid < pfs->numnodes; nodeid++ )
01793  {
01794   node = &pfs->nodelist[nodeid];
01795   PFSGeoClstPtNormPlane( &refplane, &node->coord, &proj_pt, &node->par );
01796  }
01797 
01798 /* To avoid round off errors, set the fixed null parametric values of
01799  * the reference point.
01800  */
01801  refnode->par.u = 0.0;
01802  refnode->par.v = 0.0;
01803 }
01804 
01805 /*==================  pfsCreateSolOrderLevel  ==================*/
01826 static int pfsCreateNextSolOrderLevel( int lev_begin, int lev_end, int *pos,
01827                                        int *solorder, int *nodevisited )
01828 {
01829  int        node_id;             /* id of reference node */
01830  PfsNode    *node;               /* pointer to reference node */
01831  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
01832  int        found_node = 0;
01833  int        i;
01834 
01835  for( i = lev_begin; i <= lev_end; i++ )
01836  {
01837   node_id = solorder[i];
01838   node = &pfs->nodelist[node_id];
01839 
01840   for( adjnode = node->adj_head; adjnode != NULL; adjnode = adjnode->next )
01841   {
01842    if( ! nodevisited[adjnode->id] )
01843    {
01844     found_node = 1;
01845     nodevisited[adjnode->id] = 1;
01846     solorder[*pos] = adjnode->id;
01847     (*pos)++;
01848    }
01849   }
01850  }
01851 
01852  return( found_node );
01853 }
01854 
01855 /*====================  pfsBuildSolOrderVec  ======================*/
01879 static void pfsBuildSolOrderVec( void )
01880 {
01881  int    *nodevisited;  /* array with flags for already visited nodes */
01882  int    lev_begin;     /* id of first node of current level in sol. order vec.*/
01883  int    lev_end;       /* id of last node of current level in sol. order vec.*/
01884  int    pos;           /* position of next node in solution order vector */
01885  int    i;
01886 
01887  if( pfs->sol_order != NULL )
01888   pfsDelSolOrderVec( pfs );
01889 
01890  pfs->sol_order = (int *)calloc( pfs->numnodes, sizeof( int ) );
01891  nodevisited = (int *)calloc( pfs->numnodes, sizeof( int ) );
01892 
01893  pfs->sol_order[0] = pfs->ref_node;
01894  for( i = 0; i < pfs->numnodes; i++ )
01895   nodevisited[i] = 0;
01896  nodevisited[pfs->ref_node] = 1;
01897 
01898  lev_begin = 0;
01899  lev_end = 0;
01900  pos = 1;
01901  while( pfsCreateNextSolOrderLevel( lev_begin, lev_end, &pos,
01902         pfs->sol_order, nodevisited ) )
01903  {
01904   lev_begin = lev_end + 1;
01905   lev_end = pos - 1;
01906  }
01907 
01908  free( nodevisited );
01909 }
01910 
01911 /*======================  pfsDelSolOrderVec  ======================*/
01916 static void pfsDelSolOrderVec( PfsSurf *surf )
01917 {
01918  if( surf->sol_order != NULL )
01919  {
01920   free( surf->sol_order );
01921   surf->sol_order = NULL;
01922  }
01923 }
01924 
01925 /*========================  pfsSolve2x2  ==========================*/
01929 static void pfsSolve2x2( double a[2][2], double b[2], double *u, double *v )
01930 {
01931  double det = a[0][0]*a[1][1] - a[0][1]*a[1][0];
01932 
01933  if( det > 0.0 )
01934  {
01935   *u = (a[1][1]*b[0] - a[0][1]*b[1]) / det;
01936   *v = (a[0][0]*b[1] - a[1][0]*b[0]) / det;
01937  }
01938  else
01939  {
01940   *u = 0.0;
01941   *v = 0.0;
01942  }
01943 }
01944 
01945 /*=====================  pfsSolveSurfPar1Pass  ====================*/
01968 static int pfsSolveSurfPar1Pass( void )
01969 {
01970  int        updated = 0;
01971  PfsNode    *node;
01972  PfsAdjNode *cur_adj;
01973  double     b[2];
01974  PFSGeoSurfPar newpar;
01975  int        i;
01976 
01977  for( i = 1; i < pfs->numnodes; i++ )
01978  {
01979   node = &pfs->nodelist[pfs->sol_order[i]];
01980   b[0] = b[1] = 0.0;
01981   newpar.u = newpar.v = 0.0;
01982   for( cur_adj = node->adj_head; cur_adj != NULL; cur_adj = cur_adj->next )
01983   {
01984    b[0] -= cur_adj->AtA[0][0] * pfs->nodelist[cur_adj->id].par.u + 
01985            cur_adj->AtA[0][1] * pfs->nodelist[cur_adj->id].par.v;
01986    b[1] -= cur_adj->AtA[1][0] * pfs->nodelist[cur_adj->id].par.u + 
01987            cur_adj->AtA[1][1] * pfs->nodelist[cur_adj->id].par.v;
01988    pfsSolve2x2( node->AtA, b, &newpar.u, &newpar.v );
01989   }
01990   if( ABS( newpar.u - node->par.u ) > pfs->iter_toler )
01991   {
01992    node->par.u = newpar.u;
01993    updated = 1;
01994   }
01995   if( ABS( newpar.v - node->par.v ) > pfs->iter_toler )
01996   {
01997    node->par.v = newpar.v;
01998    updated = 1;
01999   }
02000  }
02001 
02002  return( updated );
02003 }
02004 
02005 /*====================  pfsNormalizeParVals  ====================*/
02013 static void pfsNormalizeParVals( void )
02014 {
02015  double    u_size;                   /* current u size of parametric box */
02016  double    v_size;                   /* current u size of parametric box */
02017  double    scale;                    /* scaling factor */
02018  int       i;                        /* counter   */
02019  
02020  if( pfs->numnodes < 1 )
02021   return;
02022 
02023 /* Compute scaling factor for normalization.
02024  */
02025  u_size = pfs->box_umax - pfs->box_umin;
02026  v_size = pfs->box_vmax - pfs->box_vmin;
02027  scale = MAX( u_size, v_size );
02028  scale = 1.0 / scale;
02029 
02030 /* Now normalize parametric coordinates using same scale factor.
02031  */
02032  for( i = 0; i < pfs->numnodes; i++ )
02033  {
02034   pfs->nodelist[i].par.u = (pfs->nodelist[i].par.u - pfs->box_umin) * scale;
02035   pfs->nodelist[i].par.v = (pfs->nodelist[i].par.v - pfs->box_vmin) * scale;
02036  }
02037 
02038 /* Finally update parametric bounding box.
02039  */
02040  pfs->box_umin = 0.0;
02041  pfs->box_umax = u_size * scale;
02042  pfs->box_vmin = 0.0;
02043  pfs->box_vmax = v_size * scale;
02044 }
02045 
02046 /*====================  pfsComputeParBoundBox  ====================*/
02050 static void pfsComputeParBoundBox( void )
02051 {
02052  int       i;                              /* counter   */
02053 
02054  if( pfs->numnodes < 1 )
02055   return;
02056 
02057  pfs->box_umin = pfs->box_umax = pfs->nodelist[0].par.u;
02058  pfs->box_vmin = pfs->box_vmax = pfs->nodelist[0].par.v;
02059 
02060  for( i = 1; i < pfs->numnodes; i++ )
02061  {
02062   if( pfs->box_umin > pfs->nodelist[i].par.u ) 
02063    pfs->box_umin = pfs->nodelist[i].par.u;
02064   if( pfs->box_umax < pfs->nodelist[i].par.u ) 
02065    pfs->box_umax = pfs->nodelist[i].par.u;
02066   if( pfs->box_vmin > pfs->nodelist[i].par.v ) 
02067    pfs->box_vmin = pfs->nodelist[i].par.v;
02068   if( pfs->box_vmax < pfs->nodelist[i].par.v ) 
02069    pfs->box_vmax = pfs->nodelist[i].par.v;
02070  }
02071 }
02072 
02073 /*=======================  pfsElemParBoundBox  ========================*/
02079 static void pfsElemParBoundBox( PfsElem *elem )
02080 {
02081  int    node;
02082  int    i;
02083 
02084  node = elem->inc[0];
02085 
02086  elem->minparbox.u =
02087  elem->maxparbox.u = pfs->nodelist[node].par.u;
02088  elem->minparbox.v =
02089  elem->maxparbox.v = pfs->nodelist[node].par.v;
02090 
02091  for( i = 1; i < 3; i++ )
02092  {
02093   node = elem->inc[i];
02094 
02095   if( pfs->nodelist[node].par.u < elem->minparbox.u )
02096       elem->minparbox.u = pfs->nodelist[node].par.u;
02097 
02098   if( pfs->nodelist[node].par.v < elem->minparbox.v )
02099       elem->minparbox.v = pfs->nodelist[node].par.v;
02100 
02101   if( pfs->nodelist[node].par.u > elem->maxparbox.u )
02102       elem->maxparbox.u = pfs->nodelist[node].par.u;
02103 
02104   if( pfs->nodelist[node].par.v > elem->maxparbox.v )
02105       elem->maxparbox.v = pfs->nodelist[node].par.v;
02106  }
02107 
02108  PFSRtreeInsert( pfs->elm2d_tree, (void *)elem, elem->minparbox.u,
02109                                                 elem->maxparbox.u,
02110                                                 elem->minparbox.v,
02111                                                 elem->maxparbox.v, 0.0, 0.0 );
02112 }
02113 
02114 /*=================  pfsComputeElemParBoundBoxes  =====================*/
02120 static void pfsComputeElemParBoundBoxes( void )
02121 {
02122  double  xmin, ymin, zmin;
02123  double  xmax, ymax, zmax;
02124  PfsElem *elem;
02125  void    *e = NULL;
02126 
02127  if( pfs->elm3d_tree != NULL )
02128  {
02129   PFSRtreeInitTraverse( pfs->elm3d_tree );
02130 
02131   while( (e = PFSRtreeTraverse( pfs->elm3d_tree,
02132                                 &xmin, &xmax, 
02133                                 &ymin, &ymax,
02134                                 &zmin, &zmax )) != NULL )
02135   {
02136    elem = (PfsElem *)e;
02137    pfsElemParBoundBox( elem );
02138   }
02139  }
02140 }
02141 
02142 /*=====================  pfsComputeElemJac  ======================*/
02146 static void pfsComputeElemJac( PfsElem *elem, 
02147                                double *xdu, double *ydu, double *zdu, 
02148                                double *xdv, double *ydv, double *zdv )
02149 {
02150  PFSGeoPoint   p1 = pfs->nodelist[elem->inc[0]].coord;
02151  PFSGeoPoint   p2 = pfs->nodelist[elem->inc[1]].coord;
02152  PFSGeoPoint   p3 = pfs->nodelist[elem->inc[2]].coord;
02153  PFSGeoSurfPar l1 = pfs->nodelist[elem->inc[0]].par;
02154  PFSGeoSurfPar l2 = pfs->nodelist[elem->inc[1]].par;
02155  PFSGeoSurfPar l3 = pfs->nodelist[elem->inc[2]].par;
02156 
02157  double area = ((l2.u - l1.u) * (l3.v - l1.v) -
02158                 (l2.v - l1.v) * (l3.u - l1.u)) * 0.5;
02159 
02160  double fact = 0.5 / area;
02161 
02162  *xdu = fact * (p1.x * (l2.v - l3.v) + 
02163                 p2.x * (l3.v - l1.v) +
02164                 p3.x * (l1.v - l2.v));
02165  *ydu = fact * (p1.y * (l2.v - l3.v) + 
02166                 p2.y * (l3.v - l1.v) +
02167                 p3.y * (l1.v - l2.v));
02168  *zdu = fact * (p1.z * (l2.v - l3.v) + 
02169                 p2.z * (l3.v - l1.v) +
02170                 p3.z * (l1.v - l2.v));
02171 
02172  *xdv = fact * (p1.x * (l3.u - l2.u) + 
02173                 p2.x * (l1.u - l3.u) +
02174                 p3.x * (l2.u - l1.u));
02175  *ydv = fact * (p1.y * (l3.u - l2.u) + 
02176                 p2.y * (l1.u - l3.u) +
02177                 p3.y * (l2.u - l1.u));
02178  *zdv = fact * (p1.z * (l3.u - l2.u) + 
02179                 p2.z * (l1.u - l3.u) +
02180                 p3.z * (l2.u - l1.u));
02181 }
02182 
02183 /*=========================  pfsNodeJacobian  =======================*/
02189 static void pfsNodeJacobian( int id )
02190 {
02191  PfsElem    *elem;               /* index of an adjacent element */
02192  PfsNode    *node;               /* pointer to reference node */
02193  PfsAdjNode *adjnode;            /* pointer to current adjacent node */
02194 
02195  double xdu, ydu, zdu;
02196  double xdv, ydv, zdv;
02197 
02198  int nelem = 0;
02199 
02200  node = &pfs->nodelist[id];
02201 
02202  node->ddu.x = 0.0;
02203  node->ddu.y = 0.0;
02204  node->ddu.z = 0.0;
02205 
02206  node->ddv.x = 0.0;
02207  node->ddv.y = 0.0;
02208  node->ddv.z = 0.0;
02209 
02210  for( adjnode = node->adj_head; adjnode != NULL; adjnode = adjnode->next )
02211  {
02212   elem = adjnode->elem;
02213 
02214   if( elem != NULL )
02215   {
02216    pfsComputeElemJac( elem, &xdu, &ydu, &zdu, &xdv, &ydv, &zdv );
02217 
02218    node->ddu.x += xdu;
02219    node->ddu.y += ydu;
02220    node->ddu.z += zdu;
02221 
02222    node->ddv.x += xdv;
02223    node->ddv.y += ydv;
02224    node->ddv.z += zdv;
02225 
02226    nelem++;
02227   }
02228  }
02229 
02230  node->ddu.x /= (double)nelem;
02231  node->ddu.y /= (double)nelem;
02232  node->ddu.z /= (double)nelem;
02233 
02234  node->ddv.x /= (double)nelem;
02235  node->ddv.y /= (double)nelem;
02236  node->ddv.z /= (double)nelem;
02237 }
02238 
02239 /*========================  pfsNodeJacobians  =======================*/
02245 static void pfsNodeJacobians( void )
02246 {
02247  int i;
02248 
02249  if(pfs->nodelist != NULL)
02250  {
02251   for(i = 0; i < pfs->numnodes; i++)
02252   {
02253    pfsNodeJacobian(i);
02254   }
02255  }
02256 }
02257 
02258 /*============================  pfsArea3d  ==========================*/
02262 static double pfsArea3d( double xa, double ya, double za, 
02263                          double xb, double yb, double zb,
02264                          double xc, double yc, double zc,
02265                          double xn, double yn, double zn )
02266 {
02267  PFSGeoPoint vba, vca, vd, normal;
02268  double area;
02269 
02270  vba.x = xb - xa;
02271  vba.y = yb - ya;
02272  vba.z = zb - za; 
02273   
02274  vca.x = xc - xa; 
02275  vca.y = yc - ya;
02276  vca.z = zc - za; 
02277  
02278  normal.x = xn; 
02279  normal.y = yn;
02280  normal.z = zn;
02281  
02282  PFSGeoCrossProd(&vba, &vca, &vd);
02283  area = PFSGeoVecLen( &vd )/2;
02284  
02285  if( PFSGeoDotProd(&vd, &normal) < 0 )
02286   area *= -1;         
02287                                                  
02288  return( area );
02289 }
02290 
02291 /*============================  pfsArea2d  ==========================*/
02295 static double pfsArea2d( double u0, double v0,
02296                          double u1, double v1,
02297                          double u2, double v2 )
02298 {
02299  double u01, v01, u02, v02;
02300 
02301  u01 = u1 - u0;
02302  v01 = v1 - v0;
02303  u02 = u2 - u0;
02304  v02 = v2 - v0;
02305 
02306  return((u01*v02 - v01*u02) * 0.5);
02307 }
02308 
02309 /*========================  pfsDistPntCurElem  ======================*/
02320 static double pfsDistPntCurElem( PFSGeoPoint *p, PFSGeoPoint *clst )
02321 {
02322  PFSGeoPoint     p0;           /* coordinates of first element node */
02323  PFSGeoPoint     p1;           /* coordinates of second element node */
02324  PFSGeoNormPlane plane;        /* normalized plane that contains element */
02325  PFSGeoSurfPar   spar;         /* parametric coordinates of closest pt on plane */
02326  double       dist;         /* distance between given point and closest pt */
02327  
02328  pfsRItrNodeCoords( cur_elem->inc[0], &p0.x, &p0.y, &p0.z );
02329  pfsRItrNodeCoords( cur_elem->inc[1], &p1.x, &p1.y, &p1.z );
02330 
02331 /* Make the normal to the plane be the normal of the current element.
02332  */
02333  plane.n = cur_elem->normal;
02334 
02335 /* Make the origin of parametric plane space be the first node of element.
02336  */
02337  plane.a = p0;
02338 
02339 /* Make the u axis of parametric plane space be from first to second element
02340  * node.  The v axis is computed by the cross-product between the normal
02341  * vector and the u axis.
02342  */
02343  PFSGeoDiffVec( &p1, &p0, &plane.u );
02344  PFSGeoVecNormalize( &plane.u, &plane.u );
02345  PFSGeoCrossProd( &plane.n, &plane.u, &plane.v );
02346 
02347 /* Project given point on element plane to get the closest point.
02348  */
02349  PFSGeoClstPtNormPlane( &plane, p, clst, &spar );
02350 
02351 /* Get distance between given point and closest point.
02352  */
02353  dist = PFSGeoDist( p, clst );
02354 
02355  return( dist );
02356 }
02357 
02358 /*========================  pfsParPntCurElemAttract  =======================*/
02372 static int pfsParPntCurElemAttract( double *x, double *y, double *z,
02373                            double *u, double *v )
02374 {
02375  double tol = COL_TOLER;
02376  double xn[3], yn[3], zn[3], un[3], vn[3];
02377  double b0, b1, b2, A;
02378  double b0c, b1c, b2c, Ac;
02379  int status_cartesiano = 1;
02380  int status_param = 1;
02381 
02382  pfsRItrNodeCoords( cur_elem->inc[0], &xn[0], &yn[0], &zn[0] );
02383  pfsRItrNodeCoords( cur_elem->inc[1], &xn[1], &yn[1], &zn[1] );
02384  pfsRItrNodeCoords( cur_elem->inc[2], &xn[2], &yn[2], &zn[2] );
02385  pfsRItrNodeParVals( cur_elem->inc[0], &un[0], &vn[0] );
02386  pfsRItrNodeParVals( cur_elem->inc[1], &un[1], &vn[1] );
02387  pfsRItrNodeParVals( cur_elem->inc[2], &un[2], &vn[2] );
02388 
02389  pfs3dGetAreaCoord( *x, *y, *z, xn, yn, zn, &b0c, &b1c, &b2c );
02390 
02391  Ac = b0c + b1c + b2c;
02392 
02393 /* Check for point outside given element
02394  */
02395  Ac = b0c + b1c + b2c;
02396  if( ((Ac + tol) < 1.0) || ((Ac - tol) > 1.0) )
02397   status_cartesiano = 0;
02398  if( ((b0c + tol) < 0.0) || ((b1c + tol) < 0.0) || ((b2c + tol) < 0.0) )
02399   status_cartesiano = 0;
02400 
02401  *u = b0c*un[0] + b1c*un[1] + b2c*un[2];
02402  *v = b0c*vn[0] + b1c*vn[1] + b2c*vn[2];
02403 
02404  if( status_cartesiano )
02405  { 
02406   pfsParGetAreaCoord( *u, *v, un, vn, &b0, &b1, &b2 );
02407  
02408  /* Check for point outside given element
02409   */
02410   A = b0 + b1 + b2;
02411   if( ((A + tol) < 1.0) || ((A - tol) > 1.0) )
02412    status_param = 0;
02413   if( ((b0 + tol) < 0.0) || ((b1 + tol) < 0.0) || ((b2 + tol) < 0.0) )
02414    status_param = 0;
02415  
02416   if( status_param )
02417   {
02418    /* Se o ponto estiver dentro do triângulo no espaço cartesiano
02419     * e no espaço paramétrico, recalcula suas coordenadas para
02420     * evitar erros devido a tolerância
02421     */
02422    if( b0c < 0.0 ) b0c = 0.0;
02423    if( b1c < 0.0 ) b1c = 0.0;
02424    if( b2c < 0.0 ) b2c = 0.0;
02425  
02426    Ac = b0c + b1c + b2c;
02427    b0c /= Ac; 
02428    b1c /= Ac; 
02429    b2c /= Ac; 
02430    *u = b0c*un[0] + b1c*un[1] + b2c*un[2];
02431    *v = b0c*vn[0] + b1c*vn[1] + b2c*vn[2];
02432  
02433    *x = b0c*xn[0] + b1c*xn[1] + b2c*xn[2];
02434    *y = b0c*yn[0] + b1c*yn[1] + b2c*yn[2];
02435    *z = b0c*zn[0] + b1c*zn[1] + b2c*zn[2];
02436    return 1;
02437   }
02438  }
02439  return 0;
02440 }   
02441 
02442 /*========================  pfsParPntCurElem  =======================*/
02454 static int pfsParPntCurElem ( double x, double y, double z,
02455                            double *u, double *v )
02456 {
02457  double tol = COL_TOLER;
02458  double xn[3], yn[3], zn[3], un[3], vn[3];
02459  double b0, b1, b2, A;
02460  double b0c, b1c, b2c, Ac;
02461  int status_cartesiano = 1;
02462  int status_param = 1;
02463 
02464  pfsRItrNodeCoords( cur_elem->inc[0], &xn[0], &yn[0], &zn[0] );
02465  pfsRItrNodeCoords( cur_elem->inc[1], &xn[1], &yn[1], &zn[1] );
02466  pfsRItrNodeCoords( cur_elem->inc[2], &xn[2], &yn[2], &zn[2] );
02467  pfsRItrNodeParVals( cur_elem->inc[0], &un[0], &vn[0] );
02468  pfsRItrNodeParVals( cur_elem->inc[1], &un[1], &vn[1] );
02469  pfsRItrNodeParVals( cur_elem->inc[2], &un[2], &vn[2] );
02470 
02471  pfs3dGetAreaCoord( x, y, z, xn, yn, zn, &b0c, &b1c, &b2c );
02472 
02473  Ac = b0c + b1c + b2c;
02474 
02475 /* Check for point outside given element
02476  */
02477  Ac = b0c + b1c + b2c;
02478  if( ((Ac + tol) < 1.0) || ((Ac - tol) > 1.0) )
02479   status_cartesiano = 0;
02480  if( ((b0c + tol) < 0.0) || ((b1c + tol) < 0.0) || ((b2c + tol) < 0.0) )
02481   status_cartesiano = 0;
02482 
02483  *u = b0c*un[0] + b1c*un[1] + b2c*un[2];
02484  *v = b0c*vn[0] + b1c*vn[1] + b2c*vn[2];
02485  
02486  if( status_cartesiano )
02487  {
02488   pfsParGetAreaCoord( *u, *v, un, vn, &b0, &b1, &b2 );
02489  
02490  /* Check for point outside given element
02491   */
02492   A = b0 + b1 + b2;
02493   if( ((A + tol) < 1.0) || ((A - tol) > 1.0) )
02494    status_param = 0;
02495   if( ((b0 + tol) < 0.0) || ((b1 + tol) < 0.0) || ((b2 + tol) < 0.0) )
02496    status_param = 0;
02497 
02498   if( status_param )
02499   {
02500    /* Point is inside triangle
02501   */
02502    return 1;
02503   }
02504  }
02505  return 0;
02506 }   
02507 
02508 /*=========================  pfs3dPntCurElem  =========================*/
02521 static int pfs3dPntCurElem( double u, double v,
02522                            double *x, double *y, double *z )
02523 {
02524  double un[3], vn[3];
02525  double xn[3], yn[3], zn[3];
02526  double b0, b1, b2, A;
02527 
02528  pfsRItrNodeCoords( cur_elem->inc[0], &xn[0], &yn[0], &zn[0] );
02529  pfsRItrNodeCoords( cur_elem->inc[1], &xn[1], &yn[1], &zn[1] );
02530  pfsRItrNodeCoords( cur_elem->inc[2], &xn[2], &yn[2], &zn[2] );
02531  pfsRItrNodeParVals( cur_elem->inc[0], &un[0], &vn[0] );
02532  pfsRItrNodeParVals( cur_elem->inc[1], &un[1], &vn[1] );
02533  pfsRItrNodeParVals( cur_elem->inc[2], &un[2], &vn[2] );
02534 
02535  pfsParGetAreaCoord( u, v, un, vn, &b0, &b1, &b2 );
02536 
02537  *x = b0*xn[0] + b1*xn[1] + b2*xn[2];
02538  *y = b0*yn[0] + b1*yn[1] + b2*yn[2];
02539  *z = b0*zn[0] + b1*zn[1] + b2*zn[2];
02540 
02541 /* Check for point outside given element
02542  */
02543  A = b0 + b1 + b2;
02544  if((A + TOLER) < 1 || (A - TOLER) > 1)
02545   return( 0 );
02546  if((b0 + TOLER) < 0 || (b1 + TOLER) < 0 || (b2 + TOLER) < 0)
02547   return( 0 );
02548 
02549 /* Point is inside triangle
02550  */
02551  return( 1 );
02552 }
02553 
02554 /*=======================  pfsParDerivCurElem  ========================*/
02569 static int pfsParDerivCurElem( double u, double v,
02570                        double *xdu, double *ydu, double *zdu,
02571                                double *xdv, double *ydv, double *zdv,
02572                                double *xdw, double *ydw, double *zdw )
02573 {
02574  double un[3], vn[3];
02575  double xdun[3], ydun[3], zdun[3];
02576  double xdvn[3], ydvn[3], zdvn[3];
02577  double xdwn[3], ydwn[3], zdwn[3];
02578  double b0, b1, b2, A;
02579 
02580  pfsRItrNodeParVals( cur_elem->inc[0], &un[0], &vn[0] );
02581  pfsRItrNodeParVals( cur_elem->inc[1], &un[1], &vn[1] );
02582  pfsRItrNodeParVals( cur_elem->inc[2], &un[2], &vn[2] );
02583 
02584  pfsRItrNodeJacobian( cur_elem->inc[0], &xdun[0], &ydun[0], &zdun[0],
02585                                        &xdvn[0], &ydvn[0], &zdvn[0]);
02586  pfsRItrNodeJacobian( cur_elem->inc[1], &xdun[1], &ydun[1], &zdun[1],
02587                                        &xdvn[1], &ydvn[1], &zdvn[1]);
02588  pfsRItrNodeJacobian( cur_elem->inc[2], &xdun[2], &ydun[2], &zdun[2],
02589                                        &xdvn[2], &ydvn[2], &zdvn[2]);
02590 
02591  pfsRItrNodeNormal( cur_elem->inc[0], &xdwn[0], &ydwn[0], &zdwn[0]);
02592  pfsRItrNodeNormal( cur_elem->inc[1], &xdwn[1], &ydwn[1], &zdwn[1]);
02593  pfsRItrNodeNormal( cur_elem->inc[2], &xdwn[2], &ydwn[2], &zdwn[2]);
02594 
02595  pfsParGetAreaCoord( u, v, un, vn, &b0, &b1, &b2 );
02596 
02597  *xdu = b0*xdun[0] + b1*xdun[1] + b2*xdun[2];
02598  *ydu = b0*ydun[0] + b1*ydun[1] + b2*ydun[2];
02599  *zdu = b0*zdun[0] + b1*zdun[1] + b2*zdun[2];
02600 
02601  *xdv = b0*xdvn[0] + b1*xdvn[1] + b2*xdvn[2];
02602  *ydv = b0*ydvn[0] + b1*ydvn[1] + b2*ydvn[2];
02603  *zdv = b0*zdvn[0] + b1*zdvn[1] + b2*zdvn[2];
02604   
02605  *xdw = b0*xdwn[0] + b1*xdwn[1] + b2*xdwn[2];
02606  *ydw = b0*ydwn[0] + b1*ydwn[1] + b2*ydwn[2];
02607  *zdw = b0*zdwn[0] + b1*zdwn[1] + b2*zdwn[2];
02608 
02609 /* Check for point outside given element
02610  */
02611  A = b0 + b1 + b2;
02612  if((A + TOLER) < 1 || (A - TOLER) > 1)
02613   return( 0 );
02614  if((b0 + TOLER) < 0 || (b1 + TOLER) < 0 || (b2 + TOLER) < 0)
02615   return( 0 );
02616 
02617 /* Point is inside triangle
02618  */
02619  return( 1 );
02620 }
02621 
02622 /*======================  pfsClstPtParLine  =======================*/
02640 static int pfsClstPtParLine( double ua, double va, double ub, double vb,
02641                              double u, double v, double *up, double *vp,
02642                              double *dist )
02643 {
02644  double u_perp, v_perp;   /* vector perpendicular to edge */
02645  double size;
02646  double perp_pa, perp_pb;
02647 
02648 /* Get normalized vector perpendicular to edge.
02649  */
02650  u_perp = vb - va;
02651  v_perp = ua - ub;
02652  size = sqrt( u_perp*u_perp + v_perp*v_perp );
02653  if( size == 0.0 )
02654   return( 0 );
02655  u_perp /= size;
02656  v_perp /= size;
02657 
02658 /* The perpendicular line passing at the given point WILL intercept the
02659  * line (ab) if the cross product (perp x pa) and (perp x pb) have 
02660  * different signs (or if the product of the cross products is negative).
02661  * If (perp x pa) or (perp x pb) is equal zero, the perpendicular line 
02662  * intersepts the node "a" or "b", respectively. 
02663  */
02664  perp_pa = ( u_perp * (va - v) ) - ( v_perp * (ua - u) );
02665  perp_pb = ( u_perp * (vb - v) ) - ( v_perp * (ub - u) );
02666  if( perp_pa == 0.0 )
02667  {
02668   *up = ua;
02669   *vp = va;
02670  }
02671  else if( perp_pb == 0.0 )
02672  { 
02673   *up = ub;
02674   *vp = vb;
02675  }
02676  else if( perp_pa * perp_pb < 0.0 )
02677  {
02678 /* Compute the intersection point of the perpendicular line passing at  
02679  * (u,v) with line (ab).
02680  */
02681   *up = X_CROSS_LINE_SHOT( ua, va, ub, vb, u, v, u_perp, v_perp );
02682   *vp = Y_CROSS_LINE_SHOT( ua, va, ub, vb, u, v, u_perp, v_perp );
02683  }
02684  else /* if( perp_pa * perp_pb > 0.0 ) */
02685  {
02686   return( 0 );
02687  }
02688 
02689 /* Compute the distance between the given point and the closest point
02690  * on edge.
02691  */
02692  *dist = Len2( u - (*up), v - (*vp) );
02693 
02694  return( 1 );
02695 }
02696 
02697 /*============================  pfsIsParPtInside  ==========================*/
02702 static int pfsIsParPtInside( PFSGeoSurfPar *p )
02703 {
02704  int ni = 0;
02705  int numloops;
02706  int loop;
02707  int node;
02708 
02709  numloops = pfsRItrNumLoops( );
02710 
02711  for( loop = 0; loop < numloops; loop++ )
02712  {
02713   int stop = 0;
02714 
02715   if( pfsRItrFirstLoopNode( loop, &node ) == PFS_SUCCESS )
02716   {
02717    int frst = node;
02718    int curr;
02719    int next;
02720 
02721    do
02722    {
02723     double p1u, p1v, p2u, p2v;
02724     curr = node;
02725 
02726     if( pfsRItrNextLoopNode( loop, curr, &node ) != PFS_SUCCESS )
02727      stop = 1;
02728 
02729     if(!stop)
02730      next = node;
02731     else
02732      next = frst;
02733 
02734     pfsRItrNodeParVals(curr, &p1u, &p1v);
02735     pfsRItrNodeParVals(next, &p2u, &p2v);
02736 
02737        /* discards horizontal edges */ 
02738     if(!(p1v == p2v) &&
02739        /* discards edges entirely above */
02740        !((p1v > p->v) && (p2v > p->v)) &&
02741        /* discards edges entirely below */
02742        !((p1v < p->v) && (p2v < p->v)) &&
02743        /* discards edges entirely to the left */
02744        !((p1u < p->u) && (p2u < p->u)))
02745     {
02746      /* if the initial point is on the same cote */
02747      if(p1v == p->v)
02748      {
02749       /* if the point is on the left and the edge is above it */
02750       if((p1u > p->u) && (p2v > p->v))
02751        ni++;
02752      }
02753      else
02754      {
02755       /* if the last point is on the same cote */
02756       if(p2v == p->v)
02757       {
02758        /* if the point is on the left and the edge is above it */
02759        if((p2u > p->u) && (p1v > p->v))
02760         ni++;
02761       }
02762       else
02763       {
02764        /* if the edge is entirely on the right */
02765        if((p1u > p->u) && (p2u > p->u))
02766         ni++;
02767        else
02768        {
02769         /* find the intersection point */
02770         double dx = p1u-p2u;
02771         double xc = p1u;
02772 
02773         /*if ( dx != 0 )*/
02774         if(fabs(dx) > TOLER)
02775          xc += (p->v-p1v)*dx / (p1v-p2v);
02776 
02777         /* if it is on the right */
02778         if(xc > p->u)
02779          ni++;
02780        }
02781       }
02782      }
02783     }
02784    } while(!stop);
02785   }
02786  }
02787 
02788  /* TRUE if the number of intersections is odd */
02789  return(ni%2 != 0);
02790 }
02791 
02792 /*=========================  pfsIsParPtOnBound  ======================*/
02797 static int pfsIsParPtOnBound( PFSGeoSurfPar *p )
02798 {
02799  int numloops;
02800  int loop;
02801  int node;
02802  double uc, vc;
02803  double un, vn;
02804  double up, vp;
02805  double dist;
02806 
02807  numloops = pfsRItrNumLoops( );
02808 
02809  for( loop = 0; loop < numloops; loop++ )
02810  {
02811   int stop = 0;
02812 
02813   if( pfsRItrFirstLoopNode( loop, &node ) == PFS_SUCCESS )
02814   {
02815    int frst = node;
02816    int curr;
02817    int next;
02818 
02819    do
02820    {
02821     curr = node;
02822 
02823     if( pfsRItrNextLoopNode( loop, curr, &node ) != PFS_SUCCESS )
02824      stop = 1;
02825 
02826     if(!stop)
02827      next = node;
02828     else
02829      next = frst;
02830 
02831     pfsRItrNodeParVals(curr, &uc, &vc);
02832     pfsRItrNodeParVals(next, &un, &vn);
02833 
02834     if( pfsClstPtParLine( uc, vc, un, vn, p->u, p->v, &up, &vp, &dist ) )
02835     {
02836      if( dist < TOLER )
02837     {
02838       p->u = up;
02839       p->v = vp;
02840       return( 1 );
02841      }
02842     }
02843    } while(!stop);
02844   }
02845  }
02846  return( 0 );
02847 }
02848 
02849 /*=========================  pfsSnapParPtToBound  ======================*/
02854 static int pfsSnapParPtToBound( PFSGeoSurfPar *p )
02855 {
02856  PFSGeoSurfPar clst;
02857  double dmin = 1e20;
02858  double dist;
02859  double ua, va, ub, vb;
02860  double up, vp;
02861  int found = 0;
02862  int numloops;
02863  int loop;
02864  int node;
02865 
02866  clst = *p;
02867 
02868  numloops = pfsRItrNumLoops( );
02869 
02870  for( loop = 0; loop < numloops; loop++ )
02871  {
02872   int stop = 0;
02873 
02874   if( pfsRItrFirstLoopNode( loop, &node ) == PFS_SUCCESS )
02875   {
02876    int frst = node;
02877    int curr;
02878    int next;
02879 
02880    do
02881    {
02882     curr = node;
02883 
02884     if( pfsRItrNextLoopNode( loop, curr, &node ) != PFS_SUCCESS )
02885      stop = 1;
02886 
02887     if(!stop)
02888      next = node;
02889     else
02890      next = frst;
02891 
02892     pfsRItrNodeParVals( curr, &ua, &va );
02893     pfsRItrNodeParVals( next, &ub, &vb );
02894 
02895     if( pfsClstPtParLine( ua, va, ub, vb, p->u, p->v, &up, &vp, &dist ) )
02896     {
02897      if( dist < dmin )
02898      {
02899       found = 1;
02900       clst.u = up;
02901       clst.v = vp;
02902       dmin = dist;
02903      }
02904     }
02905    } while(!stop);
02906   }
02907  }
02908 
02909  if( !found )
02910   return( 0 );
02911 
02912  *p = clst;
02913 
02914  return( 1 );
02915 }
02916 
02917 /*=======================  pfsChkProxElemNode  ========================*/
02933 static int pfsChkProxElemNode( PfsElem *elem, double *u, double *v, int *ni )
02934 {
02935  double un[3], vn[3];
02936  double b0, b1, b2;
02937  int    na;
02938  int    found = 1;
02939 
02940  pfsRItrNodeParVals( elem->inc[0], &un[0], &vn[0] );
02941  pfsRItrNodeParVals( elem->inc[1], &un[1], &vn[1] );
02942  pfsRItrNodeParVals( elem->inc[2], &un[2], &vn[2] );
02943 
02944  pfsParGetAreaCoord( *u, *v, un, vn, &b0, &b1, &b2 );
02945 
02946  /* Caso uma das áreas seja igual a um, considerando uma certa
02947   * tolerância, o pto está sobre um nó ou muito próximo a ele 
02948   */
02949  if( fabs( b0-1.0 ) < COL_TOLER )      na = 0;
02950  else if( fabs( b1-1.0 ) < COL_TOLER ) na = 1;
02951  else if( fabs( b2-1.0 ) < COL_TOLER ) na = 2;
02952  else found = 0;
02953    
02954  /* o pto é atraído para a posição do nó 
02955   */
02956  if( found )
02957  {
02958   *u = un[na];
02959   *v = vn[na];
02960   *ni = elem->inc[na];
02961   return( 1 );
02962  }
02963  return( 0 );
02964 }
02965 
02966 /*=========================  pfsChkProxElemEdge  ==========================*/
02987 static int pfsChkProxElemEdge( PfsElem *elem, double *u, double *v, 
02988                                int *type, int *ni, int *nj )
02989 {
02990  double un[3], vn[3];
02991  double b0, b1, b2;
02992  int    na, nb;
02993  double du, dv;
02994  double tp;
02995  int    found = 1;
02996 
02997  pfsRItrNodeParVals( elem->inc[0], &un[0], &vn[0] );
02998  pfsRItrNodeParVals( elem->inc[1], &un[1], &vn[1] );
02999  pfsRItrNodeParVals( elem->inc[2], &un[2], &vn[2] );
03000 
03001  pfsParGetAreaCoord( *u, *v, un, vn, &b0, &b1, &b2 );
03002 
03003  /* Caso uma das áreas seja igual a um, considerando uma certa
03004   * tolerância, o pto está sobre um nó ou muito próximo a ele 
03005   */
03006  if( fabs( b1 ) < COL_TOLER && fabs( b2 ) < COL_TOLER )      na = 0;
03007  else if( fabs( b0 ) < COL_TOLER && fabs( b2 ) < COL_TOLER ) na = 1;
03008  else if( fabs( b0 ) < COL_TOLER && fabs( b1 ) < COL_TOLER ) na = 2;
03009  else found = 0;
03010    
03011  /* o pto é atraído para a posição do nó 
03012   */
03013  if( found )
03014  {
03015   *u = un[na];
03016   *v = vn[na];
03017   *ni = elem->inc[na];
03018   *type = NODE;
03019   return( 1 );
03020  }
03021 
03022  /* Caso uma das áreas seja praticamente nula, o pto está sobre uma
03023   * aresta ou muito próximo a ela 
03024   */
03025  if( fabs( b0 ) < COL_TOLER && 
03026      fabs( b1 ) > COL_TOLER && fabs( b2) > COL_TOLER ) 
03027  {
03028   na = 1;
03029   nb = 2;
03030  }
03031  else if( fabs( b1 ) < COL_TOLER && 
03032           fabs( b0 ) > COL_TOLER && fabs( b2 ) > COL_TOLER ) 
03033  { 
03034   na = 0;
03035   nb = 2;
03036  }
03037  else if( fabs( b2 ) < COL_TOLER &&
03038           fabs( b0 ) > COL_TOLER && fabs( b1 ) > COL_TOLER )
03039  { 
03040   na = 0;
03041   nb = 1;
03042  }
03043  else return( 0 ); 
03044 
03045  *ni = elem->inc[na];
03046  *nj = elem->inc[nb];
03047  *type = EDGE;
03048 
03049  /* Atrai o pto para a posição da projeção do pto na aresta. 
03050   */
03051  du = un[nb] - un[na];
03052  dv = vn[nb] - vn[na];
03053  if( ( fabs(du) < TOLER ) && ( fabs(dv) < TOLER ) ) 
03054   return( 0 );
03055 
03056  /* Faz uma verificação para ver se a  projeção do ponto está
03057   * realmente sobre a aresta*/
03058  tp = (du*(*u - un[na]) + dv*(*v - vn[na])) / (du*du + dv*dv);
03059  if( tp <= 0.0 )
03060  {
03061   tp = 0.0;
03062   *ni = elem->inc[na];
03063   *type = NODE;
03064  } 
03065  else if( tp >= 1.0 )
03066  {
03067   tp = 1.0;
03068   *ni = elem->inc[nb];
03069   *type = NODE;
03070  }
03071  *u = un[na] + tp*du;
03072  *v = vn[na] + tp*dv;
03073  
03074  return( 1 );
03075 }
03076 
03077 /*========================  pfsShotXLine  =========================*/
03103 static int pfsShotXLine( PfsElem *elem, double u0, double v0,
03104                          double u_shot, double v_shot,
03105                         int na, int nb, double *u1, double *v1,
03106                         int *type, int *n_inter )
03107 {
03108  double size;
03109  double shot_0a, shot_0b;
03110  double ua, va, ub, vb;
03111  int    aux_type;
03112 
03113  pfsRItrNodeParVals( na, &ua, &va );
03114  pfsRItrNodeParVals( nb, &ub, &vb );
03115 
03116 /* Normalize shot vector.
03117  */
03118  size = sqrt( u_shot*u_shot + v_shot*v_shot );
03119  if( size == 0.0 )
03120   return( 0 );
03121  u_shot /= size;
03122  v_shot /= size;
03123 
03124 /* The shot vector WILL intercept line (ab) if the cross product 
03125  * (shot x 0a) and (shot x 0b) have diferent signs (or if the product
03126  * of the cross products is negative). If (shot x 0a) or (shot x 0b) 
03127  * is equal zero, the shot intersepts the node "a" or "b", 
03128  * respectively. 
03129  */
03130  shot_0a = ( u_shot * (va - v0) ) - ( v_shot * (ua - u0) );
03131  shot_0b = ( u_shot * (vb - v0) ) - ( v_shot * (ub - u0) );
03132  if( shot_0a == 0.0 )
03133  {
03134   *u1 = ua;
03135   *v1 = va;
03136   aux_type = NODE;
03137   *n_inter = na;
03138  }
03139  else if( shot_0b == 0.0 )
03140  { 
03141   *u1 = ub;
03142   *v1 = vb;
03143   aux_type = NODE;
03144   *n_inter = nb;
03145  }
03146  else if( shot_0a * shot_0b < 0.0 )
03147  {
03148 /* Compute the intersection point of the shot line passing at  
03149  * (u0,v0) with line (ab).
03150  */
03151  *u1 = X_CROSS_LINE_SHOT( ua, va, ub, vb, u0, v0, u_shot, v_shot );
03152  *v1 = Y_CROSS_LINE_SHOT( ua, va, ub, vb, u0, v0, u_shot, v_shot );
03153  aux_type = EDGE;
03154  }
03155  else if( shot_0a * shot_0b > 0.0 )
03156  {
03157   return( 0 );
03158  }
03159 
03160 /* Check to see if the intersection point, as seem from the starting 
03161  * point, is in the same direction of the shot vector.  This is known
03162  * by checking the sign of the dot product between a vector from the
03163  * starting point to the inserction point and the shot vector.
03164  */
03165  if( (((*u1 - u0) * u_shot) + ((*v1 - v0) * v_shot) ) <= 0.0 )
03166  {
03167   return( 0 );
03168  }
03169 
03170  if( ( aux_type == EDGE ) && ( pfsChkProxElemNode( elem, u1, v1, n_inter ) ) )
03171  {
03172   *type = NODE;
03173  }
03174  else
03175  {
03176   *type = aux_type;
03177  }
03178  return( 1 );
03179 }
03180 
03181 /*=========================  pfsNodeShot  =========================*/
03198 static int pfsNodeShot( PfsElem *init_elem, double u0, double v0, 
03199                         double u_shot, double v_shot,
03200                         PfsElem **end_elem, double *u1, double *v1, 
03201                         int *type, int *ni, int *nj )
03202 {
03203  PfsNode    *node = &pfs->nodelist[*ni];
03204  PfsAdjNode *adjnode; /* ponteiro para os nós adjacentes */
03205  PfsElem    *elem;       /* ponteiro para os triângulos adjacentes */
03206  int        na, nb;
03207  int        i;
03208  int        n_inter;
03209 
03210  /* Verifica se o tiro intercepta as arestas opostas ao nó ou se
03211   * intercepta os nós das arestas.
03212   */
03213  for( adjnode = node->adj_head;
03214       ( adjnode!= NULL ) && ( adjnode->elem != NULL );
03215       adjnode = adjnode->next )
03216  {
03217   elem = adjnode->elem;
03218 
03219   if( ( elem != NULL ) && ( elem == init_elem ) )
03220    continue;
03221 
03222   /* Pego os nós das arestas opostas */
03223   na = adjnode->id;
03224  
03225   for( i=0; 
03226        i<3 && ( ( elem->inc[i] == *ni ) || ( elem->inc[i] == na ) );
03227        i++ ) ;
03228   nb = elem->inc[i];
03229 
03230   if( pfsShotXLine( elem, u0, v0, u_shot, v_shot, na, nb,
03231                     u1, v1, type, &n_inter ) )
03232   {
03233    *end_elem = elem;
03234    if(*type == NODE ) 
03235    {
03236     *ni = n_inter;
03237    }
03238    else if( *type == EDGE ) 
03239    {
03240     *ni = na;
03241     *nj = nb;
03242    }
03243     return( 1 ); 
03244    }
03245  }
03246 
03247  /* caso o ponto esteja inicialmente sobre um nó da fronteira
03248   * da malha, não se conheça o triangulo de origem (init_elem) 
03249   * e não ocorra interseção com os triângulos adjacentes ao nó é 
03250   * porque o tiro está na direção da face externa. Sendo assim, 
03251   * toma-se como triangulo final o primeiro triangulo adjacente ao nó.  
03252   *             ______ _______
03253   *             \    / \    / \
03254   *              \  /   \  /  <--- end_elem
03255   *               \/_____\/_____\  <--- fronteira
03256   *                      |
03257   *                      |
03258   *                     \|/ tiro
03259   */
03260   
03261 
03262  if( ( adjnode != NULL ) && ( adjnode->elem == NULL ) )
03263  {
03264   if(init_elem == NULL ) 
03265    *end_elem =  node->adj_head->elem;
03266   else
03267    *end_elem = init_elem;
03268   *type |= LOOP;
03269   return( 1 ); 
03270  }
03271  printf("\n%d\tPfsNodeShot - Nenhuma aresta ou no foram interceptados\n", pfs_node );
03272  return( 0 );
03273 }
03274 
03275 /*=========================  pfsEdgeShot  =========================*/
03292 static int pfsEdgeShot( PfsElem *init_elem, double u0, double v0, 
03293                         double u_shot, double v_shot,
03294                         PfsElem **end_elem, double *u1, double *v1, 
03295                         int *type, int *ni, int *nj )
03296 {
03297  PfsElem *elem;
03298  PfsElem *e_left, *e_right;
03299  int     na, nb;  
03300  int     boundary = 0;
03301  int     first = 1;
03302  int     i;
03303  int     n_inter;  
03304 
03305  /* pega os triangulos adjacentes a aresta */
03306  pfsGetEdgeAdjElems( *ni, *nj, &e_left, &e_right );
03307 
03308  /* verifica se a aresta está na fronteira da malha */
03309  if( ( e_left == NULL ) || ( e_right == NULL ) )
03310   boundary = 1;
03311 
03312  /* A busca é feita no triangulo a esquerda e em seguida no 
03313   * triangulo a direita. Caso a aresta esteja na fronteira da malha
03314   * ou seja conhecido o triangulo de onde o tiro se originou 
03315   * (init_elem não nulo) a busca é feita em apenas um dos 
03316   * triângulos. 
03317   */
03318  if( ( e_left != NULL ) && ( e_left != init_elem ) )
03319  {
03320   elem = e_left;
03321  }
03322  else
03323  {
03324   elem = e_right;
03325  } 
03326 
03327  if( elem )
03328  {
03329   /* verifica se ocorre interseção do tiro com as arestas dos 
03330    * triângulos adjacentes com exceção da aresta sobre a qual o pto 
03331    * se encontra.
03332    */
03333   do{
03334    na = elem->inc[0]; 
03335    for( i=0; i<3; i++ )
03336    {
03337     nb = elem->inc[(i+1)%3];
03338   
03339     /* se for a aresta sobre a qual o pto está, não faz o teste */
03340     if( ( ( na == *ni ) && (nb == *nj ) ) ||
03341         ( ( na == *nj ) && (nb == *ni ) ) )
03342     {
03343      na = nb;
03344      continue;
03345     }
03346      
03347     if( pfsShotXLine( elem, u0, v0, u_shot, v_shot, na, nb,
03348                       u1, v1, type, &n_inter ) )
03349     {
03350      *end_elem = elem;
03351      if(*type == NODE ) 
03352      {
03353       *ni = n_inter;
03354      }
03355      else if( *type == EDGE ) 
03356      {
03357       *ni = na;
03358       *nj = nb;
03359      }
03360      return( 1 ); 
03361     }
03362     na = nb;
03363    }
03364    elem = ( elem == e_left ) ? e_right : NULL;
03365   }while( !boundary && ( elem == e_right )  && ( elem != init_elem ) );
03366  }
03367 
03368  /* caso o ponto esteja inicialmente sobre uma aresta da fronteira
03369   * da malha, não se conheça o triangulo de origem (init_elem) 
03370   * e não ocorra interseção com o triângulo adjacente à aresta é 
03371   * porque o tiro está na direção da face externa e o triangulo 
03372   * origem é o único triângulo adjacente. Sendo assim, o triangulo
03373   * final será igual ao único adjacente a aresta.  
03374   *             ______ _______
03375   *             \    / \    / \
03376   *              \  /   \  /   \
03377   *               \/_____\/_____\  <--- fronteira
03378   *                   |
03379   *                   |
03380   *                  \|/ tiro
03381   */
03382  if( boundary )
03383  {
03384   if(init_elem == NULL ) 
03385    *end_elem = ( e_left != NULL ) ? e_left : e_right;
03386   else
03387    *end_elem = init_elem;
03388 
03389   *u1 = u0;
03390   *v1 = v0;
03391   *type |= LOOP;
03392   return( 1 ); 
03393  }
03394  printf("\n%d PfsEdgeShot - Nenhuma aresta ou no foram interceptados\n", pfs_node );
03395  return( 0 ); 
03396 }
03397 
03398 /*=========================  pfsFaceShot  =========================*/
03407 static int pfsFaceShot( PfsElem *init_elem, double u0, double v0, 
03408                         double u_shot, double v_shot,
03409                         PfsElem **end_elem, double *u1, double *v1, 
03410                         int *type, int *ni, int *nj )
03411 {
03412  int     na, nb;
03413  int     i;
03414  int     n_inter;
03415 
03416  /* Verifica se o tiro intercepta as arestas 
03417   */
03418  for( i=0; i<3; i++ )
03419  {
03420   /* Pego os nós das arestas opostas */
03421   na = init_elem->inc[i];
03422   nb = init_elem->inc[(i+1)%3];
03423  
03424   if( pfsShotXLine( init_elem, u0, v0, u_shot, v_shot, na, nb,
03425                     u1, v1, type, &n_inter ) )
03426   {
03427    *end_elem = init_elem;
03428    if(*type == NODE ) 
03429    {
03430     *ni = n_inter;
03431    }
03432    else if( *type == EDGE ) 
03433    {
03434     *ni = na;
03435     *nj = nb;
03436    }
03437    return( 1 ); 
03438   }
03439  }
03440  printf("\n%d\tPfsFaceShot - Nenhuma aresta ou nó foram interceptados\n", pfs_node );
03441  return( 0 );
03442 }
03443 
03444 /*===========================  pfsLoopShot ========================*/
03456 static int pfsLoopShot( PfsElem *init_elem, double u0, double v0, 
03457                         double u_shot, double v_shot,
03458                         PfsElem **end_elem, double *u1,
03459                         double *v1, int *type, int *ni, int *nj )
03460 {
03461  int           prev_id, cur_id;
03462  double        cur_len, len; 
03463  int           found = 0;
03464  int           aux_type, cur_type;
03465  PFSGeoPoint   p0, p_cur;
03466  double        u_inter, v_inter;
03467  int           ni_ref, nj_ref;
03468  int           n_inter;
03469  int           first;
03470  PfsNode       *prev_node;    
03471  PfsElem       *elem;
03472 
03473  ni_ref = *ni;
03474  nj_ref = *nj;
03475 
03476  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1)
03477             || (pfs->numloops < 1) )
03478   return( 0 );
03479 
03480  if( ( pfs->nodelist[*ni].type != NODE_BOUNDARY ) || 
03481      ( ( *type & EDGE ) && 
03482        ( pfs->nodelist[*nj].type != NODE_BOUNDARY ) ) )
03483   return( 0 );
03484 
03485 /* Calcula coordenada cartesiana do pto de partida do tiro */
03486  if( *type & NODE ) 
03487   pfsRItrNodeCoords( ni_ref, &p0.x, &p0.y, &p0.z );
03488  else
03489   pfs3dPntCurElem( u0, v0, &p0.x, &p0.y, &p0.z );
03490 
03491 /* Percorre o loop por onde o tiro saiu e verifico se o tiro está 
03492  * interceptando outra aresta do loop.
03493  * Quando o tipo do ponto de interseção no loop for NODE,  
03494  * não verifica-se a interseção do tiro com as arestas do loop
03495  * adjacentes ao nó ni.
03496  * Qdo o tipo é EDGE, não testa a interseção do tiro com a aresta  
03497  * ninj. Qdo o tipo é FREE_FACE, verifica-se a interseção com todas
03498  * as arestas do loop. 
03499  */
03500  if( *type & NODE ) 
03501   prev_id = pfs->nodelist[ni_ref].adj_head->id; 
03502  else if( *type & EDGE ) 
03503   prev_id = nj_ref;
03504  else if( *type & FREE_FACE )
03505  {
03506   prev_id = ni_ref;
03507   first = 1; /*ao invés do for, o loop seria "do ... while" */
03508  }
03509 
03510  for( prev_node = &pfs->nodelist[prev_id], 
03511       cur_id = prev_node->adj_head->id; 
03512       ( ( *type & NODE ) && ( cur_id != ni_ref ) ) ||
03513       ( ( *type & EDGE ) && ( prev_id != ni_ref ) ) ||
03514       ( ( *type & FREE_FACE ) && 
03515         ( first || ( prev_id != ni_ref ) ) ); 
03516       prev_node = &pfs->nodelist[prev_id], 
03517       cur_id = prev_node->adj_head->id )
03518  {
03519   first = 0;
03520   elem = prev_node->adj_head->elem;
03521   if( pfsShotXLine( elem, u0, v0, u_shot, v_shot, 
03522                     prev_id, cur_id,  
03523                     &u_inter, &v_inter, &cur_type, &n_inter ) )
03524   {
03525    pfsRSetCurrElem( elem );
03526 /* Coordenada cartesiana do pto do loop interceptado pelo tiro 
03527  */
03528    pfs3dPntCurElem( u_inter, v_inter, &p_cur.x, &p_cur.y, &p_cur.z );
03529 
03530 /* Distância entre o nó interceptado e o pto de partida do tiro 
03531  */
03532    cur_len = PFSGeoDist( &p_cur, &p0 );
03533    
03534 /* Mantém o pto de interseção mais próximo ao pto de partida 
03535  */ 
03536    if( !found || ( cur_len < len ) )
03537    {
03538     if( cur_type == NODE ) 
03539     {
03540      *ni = n_inter;
03541     }
03542     else if( cur_type == EDGE ) 
03543     {
03544      *ni = prev_id;
03545      *nj = cur_id;
03546     }
03547     len = cur_len;
03548     *u1 = u_inter;
03549     *v1 = v_inter;
03550     aux_type = cur_type;
03551     found = 1;
03552    }
03553   }
03554   prev_id = cur_id;
03555  }
03556  *end_elem = init_elem;
03557  
03558  if( found )
03559   *type = aux_type;
03560  else
03561   *type = FREE_FACE;
03562  
03563  return( 1 ); 
03564 }
03565 
03566 /*======================  pfsUpdateShotLen  =======================*/
03597 static int pfsUpdateShotLen( double u0, double v0, PFSGeoPoint *p0, 
03598                              double *u1, double *v1, PFSGeoPoint *p1, 
03599                              double *len )
03600 {
03601  double cur_len;
03602  PFSGeoPoint shot;
03603 
03604 /* consulta a coordenada cartesiana da posição final do tiro 
03605  */
03606  pfs3dPntCurElem( *u1, *v1, &p1->x, &p1->y, &p1->z );
03607 
03608 /* calcula a distância entre a posição final e inicial do tiro 
03609  */
03610  PFSGeoDiffVec( p1, p0, &shot );
03611  cur_len = PFSGeoVecLen( &shot );
03612   
03613 /* caso o tiro tenha ultrapassado o comprimento necessário, 
03614  * recalcula a nova posiçao
03615  */
03616  if( cur_len > *len )
03617  {
03618 #if 1
03619   double ratio = *len/cur_len;
03620 
03621   *u1 = u0 + ( *u1 - u0 ) * ratio;
03622   *v1 = v0 + ( *v1 - v0 ) * ratio;
03623 
03624  /* consulta a coordenada cartesiana da posição final do tiro 
03625   */
03626   if( !pfs3dPntCurElem( *u1, *v1, &p1->x, &p1->y, &p1->z ) )
03627   {
03628    if( !_loop_ ) 
03629     printf( "\n%d pfsUpdateShotLen\n", pfs_node );
03630   }
03631   return( 1 );
03632 #else
03633  /* normaliza o vetor que representa a direção do tiro no espaço
03634   * cartesiano e escala para ele ter apenas o tamanho que falta
03635   * percorrer.
03636   */
03637   PFSGeoVecNormalize( &shot , &shot );
03638   PFSGeoProdScalVec( &shot, len, &shot );
03639 
03640  /* calcula a posição final do tiro no espaço cartesiano 
03641   */
03642   PFSGeoSumVec( p0, &shot, p1 );
03643 
03644  /* calcula a posição final do tiro no espaço paramétrico 
03645   */
03646   pfsParPntCurElemAttract( &p1->x, &p1->y, &p1->z, u1, v1 );
03647   *len = 0.0;
03648   return( 1 );
03649 #endif
03650  }
03651  else
03652  {
03653  /* calcula o comprimento q ainda falta percorrer 
03654   */
03655   *len -= cur_len; 
03656   if( *len < TOLER )
03657    return( 1 );
03658   else
03659    return( 0 );
03660  }
03661 }
03662 
03663 /*==================  pfsFinishFreeFaceShotLen  ===================*/
03686 static void pfsFinishFreeFaceShotLen( double u0, double v0, PFSGeoPoint *p0, 
03687                                       double u_shot, double v_shot, double len,
03688                                       double *u1, double *v1, PFSGeoPoint *p1 )  
03689 {
03690  PFSGeoPoint shot;
03691 
03692 /* calcula a coordenada paramétrica de um pto qualquer na direção do
03693  * tiro. 
03694  */
03695  *u1 = u0+u_shot; 
03696  *v1 = v0+v_shot; 
03697 
03698 /* calculo a coord cartesiana desse ponto 
03699  */
03700  pfs3dPntCurElem( *u1, *v1, &p1->x, &p1->y, &p1->z ); 
03701  
03702 /* calculo o vetor do tiro normalizado no espaço cartesiano e 
03703  * escala pro comprimento q ainda falta 
03704  */
03705  PFSGeoDiffVec( p1, p0, &shot );
03706  PFSGeoVecNormalize( &shot , &shot );
03707  PFSGeoProdScalVec( &shot, &len, &shot );
03708  
03709 /* calcula a posição final do tiro no espaço cartesiano 
03710 */
03711  PFSGeoSumVec( p0, &shot, p1 ); 
03712 
03713 /* calcula a posição final do tiro no espaço paramétrico 
03714  */
03715  pfsParPntCurElemAttract( &p1->x, &p1->y, &p1->z, u1, v1 );
03716 }
03717 
03718  /*========================  pfsShotSolve  =========================*/
03756  static int pfsShotSolve( PfsElem *init_elem, double u0, double v0, 
03757                           PFSGeoPoint p0, double u_shot, double v_shot,
03758                           PfsElem **end_elem, double *u1, double *v1,
03759                           PFSGeoPoint *p1, int *type, int *ni, int *nj,
03760                           double *len )
03761  {
03762   int status = 0;
03763   int loop_in = 0; /* indica se o tiro está entrando na malha */
03764   _loop_ = 0;
03765 
03766   switch( *type )
03767   {
03768    case NODE:
03769     status = pfsNodeShot( init_elem, u0, v0, u_shot, v_shot, 
03770                           end_elem, u1, v1, type, ni, nj );
03771     break;
03772    case EDGE:
03773     status = pfsEdgeShot( init_elem, u0, v0, u_shot, v_shot, 
03774                           end_elem, u1, v1, type, ni, nj );
03775     break;
03776    case FACE:
03777     status = pfsFaceShot( init_elem, u0, v0, u_shot, v_shot, 
03778                           end_elem, u1, v1, type, ni, nj );
03779     break;
03780   default:
03781    if( *type & LOOP )
03782    {
03783     _loop_ = 1;
03784     status = pfsLoopShot( init_elem, u0, v0, u_shot, v_shot,
03785                           end_elem, u1, v1, type, ni, nj );
03786     loop_in = 1;
03787    }
03788    break;
03789  }
03790  
03791  /* Verifica se ocorreu algum erro e, caso não tenha ocorrido,
03792   * atualiza o elemento corrente. 
03793   */
03794  if( !status )
03795   return( 0 );
03796  else if( *end_elem != NULL )
03797   pfsRSetCurrElem( *end_elem );
03798   
03799   if( init_elem == NULL )
03800    pfs3dPntCurElem( u0, v0, &p0.x, &p0.y, &p0.z );
03801   
03802  /* Se não encontrou interseção é pque o tiro sai da malha 
03803   */
03804  if( *type == FREE_FACE )
03805  {
03806   pfsFinishFreeFaceShotLen( u0, v0, &p0, u_shot, v_shot, *len, u1, v1, p1 );  
03807  }
03808  else if(  ( *type & LOOP ) || 
03809            !pfsUpdateShotLen( u0, v0, &p0, u1, v1, p1, len ) )
03810  {
03811   if( *type & LOOP ) 
03812   {
03813    p1->x = p0.x;
03814    p1->y = p0.y;
03815    p1->z = p0.z;
03816   } 
03817   else if( loop_in ) 
03818   {
03819 /* Qdo o tiro atravessa um loop, ao entrar novamente na malha
03820  * o tipo será sempre nó ou aresta e a busca deve ser feita em
03821  * todos os elementos adjacentes. Para isso, o elemento inicial
03822  * do próximimo passo tem q ser nulo
03823  */
03824    *end_elem = NULL;
03825   }
03826 
03827   pfsShotSolve( *end_elem, *u1, *v1, *p1,
03828                 u_shot, v_shot, end_elem, u1, v1, p1, type, 
03829                 ni, nj, len );  
03830  }
03831  return( 1 );
03832 }
03833 
03834 /*
03835 ** ---------------------------------------------------------------
03836 ** Entry points begin here:
03837 */
03838 
03839 /*=========================  pfsRInitSurf  =========================*/
03840 
03841 void *pfsRInitSurf( int mxnds, int mxels )
03842 {
03843  PfsSurf *newsurf;
03844 
03845 /* Allocate memory for a new surface.
03846  */
03847  newsurf = (PfsSurf *)malloc( sizeof( PfsSurf ) );
03848  newsurf->box_xmin = newsurf->box_xmin = 0.0;
03849  newsurf->box_ymin = newsurf->box_ymin = 0.0;
03850  newsurf->box_zmin = newsurf->box_zmin = 0.0;
03851  newsurf->box_umin = newsurf->box_umin = 0.0;
03852  newsurf->box_vmin = newsurf->box_vmin = 0.0;
03853 
03854 /* Allocate memory for node list vector.
03855  */
03856  newsurf->maxnodes = mxnds;
03857  newsurf->nodelist = (PfsNode *)calloc( newsurf->maxnodes, sizeof( PfsNode ) );
03858 
03859 /* Create two R-trees: one indexed by 3D element bounding box and
03860  * the other indexed by parametric element bounding box.
03861  */
03862  newsurf->elm2d_tree = PFSRtreeCreate( );
03863  newsurf->elm3d_tree = PFSRtreeCreate( );
03864 
03865 /* Reset node solution order vector.
03866  */
03867  newsurf->sol_order = NULL;
03868 
03869 /* Initialize total number of nodes and elements.
03870  */
03871  newsurf->numnodes = 0;
03872  newsurf->numelems = 0;
03873 
03874 /* Initialize loops data.
03875  */
03876  newsurf->numloops = 0;
03877  newsurf->looplist = NULL;
03878 
03879 /* Initialize reference element and reference node.
03880  */
03881  newsurf->ref_elem = NULL;
03882  newsurf->ref_node = -1;
03883 
03884  return( newsurf );
03885 }
03886 
03887 /*=======================  pfsRActivateSurf  =======================*/
03888 
03889 void pfsRActivateSurf( void *surf )
03890 {
03891  if( !surf )
03892   return;
03893 
03894  pfs = (PfsSurf *)surf;
03895  cur_elem = NULL;
03896  curr_ielem = NULL;
03897 }
03898 
03899 /*=========================  pfsRFreeSurf  =========================*/
03900 
03901 void pfsRFreeSurf( void *surf )
03902 {
03903  PfsSurf *delsurf;
03904 
03905  if( !surf )
03906   return;
03907 
03908  delsurf = (PfsSurf *)surf;
03909 
03910  pfsDelNodeList( delsurf );
03911  pfsDelElemList( delsurf );
03912  pfsDelSolOrderVec( delsurf );
03913 
03914  cur_elem = NULL;
03915  curr_ielem = NULL;
03916 
03917  free( delsurf );
03918 }
03919 
03920 /*==========================  pfsRAddNode  =========================*/
03921 
03922 int pfsRAddNode( double x, double y, double z )
03923 {
03924  int    node_id;
03925 
03926  if( !pfs )
03927   return( PFS_NO_SURFACE_DEFINED );
03928 
03929  if( pfs->numnodes == pfs->maxnodes )
03930  {
03931   pfs->maxnodes *= 2;
03932   pfs->nodelist = (PfsNode *)realloc( pfs->nodelist, 
03933                                       pfs->maxnodes*sizeof( PfsNode ) );
03934  }
03935 
03936  node_id = pfs->numnodes;
03937  pfs->nodelist[node_id].coord.x = x;
03938  pfs->nodelist[node_id].coord.y = y;
03939  pfs->nodelist[node_id].coord.z = z;
03940  pfs->nodelist[node_id].par.u = 0.0;
03941  pfs->nodelist[node_id].par.v = 0.0;
03942  pfs->nodelist[node_id].AtA[0][0] = 0.0;
03943  pfs->nodelist[node_id].AtA[0][1] = 0.0;
03944  pfs->nodelist[node_id].AtA[1][0] = 0.0;
03945  pfs->nodelist[node_id].AtA[1][1] = 0.0;
03946  pfs->nodelist[node_id].degree = 0;
03947  pfs->nodelist[node_id].adj_head = NULL;
03948  pfs->nodelist[node_id].type = NODE_INTERIOR;
03949 
03950  pfs->numnodes++;
03951 
03952  return( node_id );
03953 }
03954 
03955 /*==========================  pfsRAddElem  =========================*/
03956 
03957 int pfsRAddElem( int v0, int v1, int v2 )
03958 {
03959  if( !pfs )
03960   return 0;
03961 
03962  curr_ielem = (PfsElem *)calloc( 1, sizeof( PfsElem ) );
03963 
03964  curr_ielem->inc[0] = v0;
03965  curr_ielem->inc[1] = v1;
03966  curr_ielem->inc[2] = v2;
03967 
03968  pfsElemNormal( curr_ielem );
03969  pfsElemCenter( curr_ielem );
03970  pfsElemLocalGradients( curr_ielem );
03971  pfsElem3dBoundBox( curr_ielem );
03972 
03973  curr_ielem->minparbox.u = 0.0;
03974  curr_ielem->minparbox.v = 0.0;
03975  curr_ielem->maxparbox.u = 0.0;
03976  curr_ielem->maxparbox.v = 0.0;
03977 
03978  pfs->numelems++;
03979 
03980  return 1;
03981 }
03982 
03983 /*=======================  pfsRCompleteSurf  =======================*/
03984 
03985 int pfsRCompleteSurf( void )
03986 {
03987  int  status;
03988 
03989  if( !pfs )
03990   return( PFS_NO_SURFACE_DEFINED );
03991 
03992 /* Build node adjacency data structure.
03993  */
03994  status = pfsBuildNodeAdj( );
03995  if( status != PFS_SUCCESS )
03996  {
03997   pfsRFreeSurf( pfs );
03998   pfs = NULL;
03999   return( status );
04000  }
04001  pfsClassifyNodes( );
04002 
04003 /* Order the adjacent node list of all nodes such that the first 
04004  * adjacent node in list is the next boundary node when 
04005  * traversing the surface boundary.
04006  */
04007  status = pfsOrderAllBdryNodeAdj( );
04008  if( status != PFS_SUCCESS )
04009  {
04010   pfsRFreeSurf( pfs );
04011   pfs = NULL;
04012   return( status );
04013  }
04014 
04015 /* Create loop list vector that contains the id of the first
04016  * node of each loop.
04017  */
04018  pfsBuildLoopList( );
04019 
04020 /* Compute mesh 3D bounding box.
04021  */
04022  pfsCompute3dBoundBox( );
04023 
04024 /* Compute node normal vectors.
04025  */
04026  pfsNodeNormals( );
04027 
04028 /* Find reference element (which contains the origin of parametric space).
04029  */
04030  pfsFindRefElem( );
04031 
04032 /* Computed conformal map coefficients for all nodes in surface.
04033  */
04034  pfsConfMapCoefficients( );
04035 
04036 /* Initialize nodal parametric values.
04037  */
04038  pfsInitParams( );
04039 
04040 /* Compute mesh parametric bounding box.
04041  */
04042  pfsComputeParBoundBox( );
04043 
04044 /* Allocated and build node solution order vector.
04045  */
04046  pfsBuildSolOrderVec( );
04047 
04048  return( PFS_SUCCESS );
04049 }
04050 
04051 /*========================  pfsRSolveSurfPar  ======================*/
04052 
04053 void pfsRSolveSurfPar( int maxnumiter )
04054 {
04055  int        numiter = 0;
04056  int        not_done = 1;
04057 
04058  if( !pfs )
04059   return;
04060 
04061  if( maxnumiter == 0 )
04062  {
04063   while( not_done )
04064   {
04065    if( ! pfsSolveSurfPar1Pass( ) )
04066     not_done = 0;
04067   }
04068  }
04069  else
04070  {
04071   while( not_done && (numiter < maxnumiter) )
04072   {
04073    numiter++;
04074    if( ! pfsSolveSurfPar1Pass( ) )
04075     not_done = 0;
04076   }
04077  }
04078 
04079 /* Compute mesh parametric bounding box.
04080  */
04081  pfsComputeParBoundBox( );
04082 }
04083 
04084 /*======================  pfsCompleteParSpace  ====================*/
04085 
04086 void pfsCompleteParSpace( void )
04087 {
04088 /* Normalized nodal parametric coordinates.
04089  */
04090  pfsNormalizeParVals( );
04091 
04092 /* Compute element parametric bounding boxes and store the 
04093  * elements in the R-tree indexed by parametric bounding boxes.
04094  */
04095  pfsComputeElemParBoundBoxes( );
04096 
04097 /* Compute avarage Jacobian (mapping derivatves) for all nodes.
04098  */
04099  pfsNodeJacobians( );
04100 }
04101 
04102 /*=======================  pfsRItr3dBoundBox  ======================*/
04103 
04104 int pfsRItr3dBoundBox( double *xmin, double *xmax,
04105                       double *ymin, double *ymax,
04106                       double *zmin, double *zmax )
04107 {
04108  if( (!pfs) || (pfs->numnodes < 1) )
04109   return( 0 );
04110 
04111  if( xmin ) *xmin = pfs->box_xmin;
04112  if( xmax ) *xmax = pfs->box_xmax;
04113  if( ymin ) *ymin = pfs->box_ymin;
04114  if( ymax ) *ymax = pfs->box_ymax;
04115  if( zmin ) *zmin = pfs->box_zmin;
04116  if( zmax ) *zmax = pfs->box_zmax;
04117 
04118  return( 1 );
04119 }
04120 
04121 /*======================  pfsRItrParBoundBox  ======================*/
04122 
04123 int pfsRItrParBoundBox( double *umin, double *umax,
04124                        double *vmin, double *vmax )
04125 {
04126  if( (!pfs) || (pfs->numnodes < 1) )
04127   return( 0 );
04128 
04129  if( umin ) *umin = pfs->box_umin;
04130  if( umax ) *umax = pfs->box_umax;
04131  if( vmin ) *vmin = pfs->box_vmin;
04132  if( vmax ) *vmax = pfs->box_vmax;
04133 
04134  return( 1 );
04135 }
04136 
04137 /*=======================  pfsRItrFirstElem  =======================*/
04138 
04139 int pfsRItrFirstElem( void )
04140 {
04141  double xmin, ymin, zmin;
04142  double xmax, ymax, zmax;
04143 
04144  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04145   return( PFS_ITERATION_END );
04146 
04147  PFSRtreeInitTraverse( pfs->elm3d_tree );
04148 
04149  cur_elem = PFSRtreeTraverse( pfs->elm3d_tree,
04150                               &xmin, &xmax, 
04151                               &ymin, &ymax,
04152                               &zmin, &zmax );
04153 
04154  cur_elemnode = 0;
04155 
04156  if( cur_elem == NULL )
04157   return( PFS_ITERATION_END );
04158 
04159  return( PFS_SUCCESS );
04160 }
04161 
04162 /*=======================  pfsRItrNextElem  ========================*/
04163 
04164 int pfsRItrNextElem( void )
04165 {
04166  double xmin, ymin, zmin;
04167  double xmax, ymax, zmax;
04168 
04169  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04170   return( PFS_ITERATION_END );
04171 
04172  cur_elemnode = 0;
04173 
04174  cur_elem = PFSRtreeTraverse( pfs->elm3d_tree,
04175                               &xmin, &xmax, 
04176                               &ymin, &ymax,
04177                               &zmin, &zmax );
04178 
04179  if( cur_elem == NULL )
04180   return( PFS_ITERATION_END );
04181 
04182  return( PFS_SUCCESS );
04183 }
04184 
04185 /*=======================  pfsRItrFirst3dElem  =======================*/
04186 
04187 int pfsRItrFirst3dElem( double xmin, double xmax,
04188                        double ymin, double ymax,
04189                        double zmin, double zmax )
04190 {
04191  double xmn, ymn, zmn;
04192  double xmx, ymx, zmx;
04193 
04194  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04195   return( PFS_ITERATION_END );
04196 
04197  PFSRtreeInitSearchBox( pfs->elm3d_tree, xmin, xmax, ymin, ymax, zmin, zmax );
04198 
04199  cur_elem = PFSRtreeSearchBox( pfs->elm3d_tree,
04200                                &xmn, &xmx, 
04201                                &ymn, &ymx,
04202                                &zmn, &zmx );
04203 
04204  cur_elemnode = 0;
04205 
04206  if( cur_elem == NULL )
04207   return( PFS_ITERATION_END );
04208 
04209  return( PFS_SUCCESS );
04210 }
04211 
04212 /*=======================  pfsRItrNext3dElem  ========================*/
04213 
04214 int pfsRItrNext3dElem( double xmin, double xmax,
04215                       double ymin, double ymax,
04216                       double zmin, double zmax )
04217 {
04218  double xmn, ymn, zmn;
04219  double xmx, ymx, zmx;
04220 
04221  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04222   return( PFS_ITERATION_END );
04223 
04224  cur_elemnode = 0;
04225 
04226  cur_elem = PFSRtreeSearchBox( pfs->elm3d_tree,
04227                                &xmn, &xmx, 
04228                                &ymn, &ymx,
04229                                &zmn, &zmx );
04230 
04231  if( cur_elem == NULL )
04232   return( PFS_ITERATION_END );
04233 
04234  return( PFS_SUCCESS );
04235 }
04236 
04237 /*=======================  pfsRItrFirstParElem  =======================*/
04238 
04239 int pfsRItrFirstParElem( double umin, double umax,
04240                         double vmin, double vmax )
04241 {
04242  double xmn, ymn, zmn;
04243  double xmx, ymx, zmx;
04244 
04245  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04246   return( PFS_ITERATION_END );
04247 
04248  PFSRtreeInitSearchBox( pfs->elm2d_tree, umin, umax, vmin, vmax, 0, 0 );
04249 
04250  cur_elem = PFSRtreeSearchBox( pfs->elm2d_tree,
04251                                &xmn, &xmx, 
04252                                &ymn, &ymx,
04253                                &zmn, &zmx );
04254 
04255  cur_elemnode = 0;
04256 
04257  if( cur_elem == NULL )
04258   return( PFS_ITERATION_END );
04259 
04260  return( PFS_SUCCESS );
04261 }
04262 
04263 /*=======================  pfsRItrNextParElem  ========================*/
04264 
04265 int pfsRItrNextParElem( double umin, double umax,
04266                        double vmin, double vmax )
04267 {
04268  double xmn, ymn, zmn;
04269  double xmx, ymx, zmx;
04270 
04271  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1) )
04272   return( PFS_ITERATION_END );
04273 
04274  cur_elemnode = 0;
04275 
04276  cur_elem = PFSRtreeSearchBox( pfs->elm2d_tree,
04277                                &xmn, &xmx, 
04278                                &ymn, &ymx,
04279                                &zmn, &zmx );
04280 
04281  if( cur_elem == NULL )
04282   return( PFS_ITERATION_END );
04283 
04284  return( PFS_SUCCESS );
04285 }
04286 
04287 /*=======================  pfsRSetCurrElem  ========================*/
04288 
04289 void pfsRSetCurrElem( void *elem )
04290 {
04291  if( elem == NULL )
04292   return;
04293 
04294  cur_elem = (PfsElem *)elem;
04295  cur_elemnode = 0;
04296 }
04297 
04298 /*=========================  pfsRGetElem  ==========================*/
04299 
04300 int pfsRGetElem( double x, double y, double z, void **elem )
04301 {
04302  int itr;
04303  double u, v;
04304 
04305  for(itr  = pfsRItrFirstElem( );
04306      itr != PFS_ITERATION_END;
04307      itr  = pfsRItrNextElem( ) )
04308  {
04309    if( pfsParPntCurElem( x, y, z, &u, &v ))
04310    {
04311      *elem = cur_elem;
04312      return(1);
04313    }
04314  }
04315  *elem = NULL;
04316 
04317  return(0);
04318 }
04319 
04320 /*=========================  pfsRGetLoopElem  ==========================*/
04321 /* Procura o elemento de um loop externo mais próximo ao ponto dado pelas
04322  * coordenadas xyz
04323  */
04324 int pfsRGetLoopElem( double x, double y, double z, void **elem )
04325 {
04326  int itr;
04327  int nloop = pfsRItrNumLoops( );
04328  int ni;   
04329  int i;
04330  double xc, yc, zc;
04331  int first = 1;
04332  PfsNode *node;
04333  double dist, dist_cur;
04334  
04335  for( i=0; i<nloop; i++ )
04336  {
04337   for(itr  = pfsRItrFirstLoopNode( i, &ni );
04338       itr != PFS_ITERATION_END;
04339       itr  = pfsRItrNextLoopNode(  i, ni, &ni ) )
04340   {
04341         node = &pfs->nodelist[ni];
04342         cur_elem = node->adj_head->elem;
04343    pfsRItrElemCenter( &xc, &yc, &zc );
04344    dist_cur = sqrt( ( x - xc ) * ( x - xc ) +
04345                     ( y - yc ) * ( y - yc ) +
04346                     ( z - zc ) * ( z - zc ) );
04347         /* calcula a distância do pto ao centro do elemento */
04348    if( first || ( dist_cur < dist ) )
04349    {
04350     dist = dist_cur;
04351     *elem = cur_elem;
04352     first = 0;
04353    }
04354   }
04355  }
04356  
04357  if( first )
04358  {
04359   *elem = NULL;
04360   return(0);
04361  }
04362  return(1);
04363 }
04364 
04365 /*=======================  pfsRItrElemNode  ========================*/
04366 
04367 int pfsRItrElemNode( int *id )
04368 {
04369  if( (!pfs) || (pfs->numnodes < 1) )
04370   return( PFS_ITERATION_END );
04371 
04372  if( cur_elem == NULL )
04373   return( PFS_ITERATION_END );
04374 
04375  if( cur_elemnode == 3 )
04376   return( PFS_ITERATION_END );
04377 
04378  *id = cur_elem->inc[cur_elemnode];
04379 
04380  cur_elemnode += 1;
04381 
04382  return( PFS_SUCCESS );
04383 }
04384 
04385 /*======================  pfsRItrElemCenter  =======================*/
04386 
04387 void pfsRItrElemCenter( double *x, double *y, double *z )
04388 {
04389  if( (!pfs) || (pfs->numnodes < 1) )
04390   return;
04391 
04392  if( cur_elem == NULL )
04393   return;
04394 
04395  *x = cur_elem->center.x;
04396  *y = cur_elem->center.y;
04397  *z = cur_elem->center.z;
04398 }
04399 
04400 /*======================  pfsRItrElemNormal  =======================*/
04401 
04402 void pfsRItrElemNormal( double *nx, double *ny, double *nz )
04403 {
04404  if( (!pfs) || (pfs->numnodes < 1) )
04405   return;
04406 
04407  if( cur_elem == NULL )
04408   return;
04409 
04410  *nx = cur_elem->normal.x;
04411  *ny = cur_elem->normal.y;
04412  *nz = cur_elem->normal.z;
04413 }
04414 
04415 /*======================  pfsRItrElem3dBox  ======================*/
04416 
04417 void pfsRItrElem3dBox( double *xmin, double *ymin, double *zmin,
04418                       double *xmax, double *ymax, double *zmax )
04419 {
04420  if( (!pfs) || (pfs->numnodes < 1) )
04421   return;
04422 
04423  if( cur_elem == NULL )
04424   return;
04425 
04426  *xmin = cur_elem->min3dbox.x;
04427  *ymin = cur_elem->min3dbox.y;
04428  *zmin = cur_elem->min3dbox.z;
04429  *xmax = cur_elem->max3dbox.x;
04430  *ymax = cur_elem->max3dbox.y;
04431  *zmax = cur_elem->max3dbox.z;
04432 }
04433 
04434 /*=====================  pfsRItrElemParBox  ======================*/
04435 
04436 void pfsRItrElemParBox( double *umin, double *vmin,
04437                        double *umax, double *vmax )
04438 {
04439  if( (!pfs) || (pfs->numnodes < 1) )
04440   return;
04441 
04442  if( cur_elem == NULL )
04443   return;
04444 
04445  *umin = cur_elem->minparbox.u;
04446  *vmin = cur_elem->minparbox.v;
04447  *umax = cur_elem->maxparbox.u;
04448  *vmax = cur_elem->maxparbox.v;
04449 }
04450 
04451 /*=======================  pfsRItrNumNodes  ========================*/
04452 
04453 int pfsRItrNumNodes( void )
04454 {
04455  if( !pfs )
04456   return( 0 );
04457 
04458  return( pfs->numnodes );
04459 }
04460 
04461 /*======================  pfsRItrNodeCoords  =======================*/
04462 
04463 void pfsRItrNodeCoords( int id, double *x, double *y, double *z )
04464 {
04465  if( (!pfs) || (pfs->numnodes < 1) )
04466   return;
04467 
04468  *x = pfs->nodelist[id].coord.x;
04469  *y = pfs->nodelist[id].coord.y;
04470  *z = pfs->nodelist[id].coord.z;
04471 }
04472 
04473 /*======================  pfsRItrNodeNormal  =======================*/
04474 
04475 void pfsRItrNodeNormal( int id, double *nx, double *ny, double *nz )
04476 {
04477  if( (!pfs) || (pfs->numnodes < 1) )
04478   return;
04479 
04480  *nx = pfs->nodelist[id].normal.x;
04481  *ny = pfs->nodelist[id].normal.y;
04482  *nz = pfs->nodelist[id].normal.z;
04483 }
04484 
04485 /*======================  pfsRItrNodeJacobian  =======================*/
04486 
04487 void pfsRItrNodeJacobian( int id, double *xdu, double *ydu, double *zdu,
04488                                  double *xdv, double *ydv, double *zdv )
04489 {
04490  if( (!pfs) || (pfs->numnodes < 1) )
04491   return;
04492 
04493  *xdu = pfs->nodelist[id].ddu.x;
04494  *ydu = pfs->nodelist[id].ddu.y;
04495  *zdu = pfs->nodelist[id].ddu.z;
04496  *xdv = pfs->nodelist[id].ddv.x;
04497  *ydv = pfs->nodelist[id].ddv.y;
04498  *zdv = pfs->nodelist[id].ddv.z;
04499 }
04500 
04501 /*=====================  pfsRItrNodeParVals  =======================*/
04502 
04503 void pfsRItrNodeParVals( int id, double *u, double *v )
04504 {
04505  if( (!pfs) || (pfs->numnodes < 1) )
04506   return;
04507 
04508  *u = pfs->nodelist[id].par.u;
04509  *v = pfs->nodelist[id].par.v;
04510 }
04511 
04512 /*=======================  pfsRItrNumLoops  ========================*/
04513 
04514 int pfsRItrNumLoops( void )
04515 {
04516  if( !pfs )
04517   return( 0 );
04518 
04519  return( pfs->numloops );
04520 }
04521 
04522 /*=====================  pfsRItrFirstLoopNode  =====================*/
04523 
04524 int pfsRItrFirstLoopNode( int loop_id, int *id )
04525 {
04526  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1)
04527             || (pfs->numloops < 1) || (loop_id >= pfs->numloops) )
04528   return( PFS_ITERATION_END );
04529 
04530  *id = pfs->looplist[loop_id];
04531 
04532  return( PFS_SUCCESS );
04533 }
04534 
04535 /*=====================  pfsRItrNextLoopNode  ======================*/
04536 
04537 int pfsRItrNextLoopNode( int loop_id, int ref_id, int *id )
04538 {
04539  PfsNode    *ref_node;           /* pointer to given reference node */
04540 
04541  if( (!pfs) || (pfs->numnodes < 1) || (pfs->numelems < 1)
04542             || (pfs->numloops < 1) )
04543   return( PFS_ITERATION_END );
04544 
04545  if( pfs->nodelist[ref_id].type != NODE_BOUNDARY )
04546   return( PFS_ITERATION_END );
04547 
04548  ref_node = &pfs->nodelist[ref_id];
04549  *id = ref_node->adj_head->id;
04550 
04551  if( *id == pfs->looplist[loop_id] )
04552   return( PFS_ITERATION_END );
04553 
04554  return( PFS_SUCCESS );
04555 }
04556 
04557 /*========================= pfsRProjectOn ==========================*/
04558 
04559 int pfsRProjectOn( double x, double y, double z,
04560                   double *u, double *v )
04561 {
04562  double dmin, xmin, xmax, ymin, ymax, zmin, zmax, dist;
04563  int kmin = 0;
04564  int itr;
04565  PFSGeoPoint p;
04566  PFSGeoPoint clst;
04567  double tol = TOLER;
04568 
04569  if(pfs == NULL)
04570   return( 0 );
04571 
04572  dmin = 1e20;
04573 
04574  p.x = x;
04575  p.y = y;
04576  p.z = z;
04577 
04578  xmin = x - tol;
04579  xmax = x + tol;
04580  ymin = y - tol;
04581  ymax = y + tol;
04582  zmin = z - tol;
04583  zmax = z + tol;
04584 
04585  for(itr  = pfsRItrFirst3dElem(xmin, xmax, ymin, ymax, zmin, zmax);
04586      itr != PFS_ITERATION_END;
04587      itr  = pfsRItrNext3dElem (xmin, xmax, ymin, ymax, zmin, zmax))
04588  {
04589   dist = pfsDistPntCurElem( &p, &clst );
04590 
04591   if(dist < dmin)
04592   {
04593    if( !pfsParPntCurElem( x, y, z, u, v ) )
04594     continue;
04595 
04596    dmin = dist;
04597    kmin++;
04598   }
04599  }
04600 
04601  if(kmin != 0)
04602   return( 1 );
04603 
04604  return 0;
04605 }
04606 
04607 /*======================== pfsSnapToBound =========================*/
04608 
04609 int pfsSnapToBound( double *u, double *v, double toler )
04610 {
04611  PFSGeoSurfPar p;
04612 
04613  if(pfs == NULL)
04614   return( 0 );
04615 
04616  p.u = *u;
04617  p.v = *v;
04618 
04619  if( !pfsSnapParPtToBound( &p ) )
04620   return( 0 );
04621 
04622  if( Len2( *u - p.u, *v - p.v ) <= toler )
04623  {
04624   *u = p.u;
04625   *v = p.v;
04626   return( 1 );
04627  }
04628 
04629  return( 0 );
04630 }
04631 
04632 /*======================== pfsRGetJacobian =========================*/
04633 
04634 int pfsRGetJacobian( double u, double v,
04635                     double *xdu, double *ydu, double *zdu,
04636                     double *xdv, double *ydv, double *zdv,
04637                     double *xdw, double *ydw, double *zdw )
04638 {
04639  PFSGeoSurfPar p;
04640  double umin, vmin, umax, vmax;
04641  double tol = 1e-3;
04642  int itr;
04643 
04644  if(pfs == NULL)
04645   return( 0 );
04646 
04647 /* In case given point is outside of surface parametric borders,
04648  * reject point.  If it is close to the boundary, update the
04649  * parametric coordinates to the coordinates of the closest point.
04650   */
04651  p.u = u;
04652  p.v = v;
04653  if( (! pfsIsParPtInside( &p )) && (! pfsIsParPtOnBound( &p )) )
04654  {
04655   return( 0 );
04656  }
04657  u = p.u;
04658  v = p.v;
04659  
04660  umin = u;
04661  vmin = v;
04662  umax = u;
04663  vmax = v;
04664 
04665  umin -= tol;
04666  vmin -= tol;
04667  umax += tol;
04668  vmax += tol;
04669 
04670  for(itr  = pfsRItrFirstParElem(umin, umax, vmin, vmax);
04671      itr != PFS_ITERATION_END;
04672      itr  = pfsRItrNextParElem(umin, umax, vmin, vmax))
04673  {
04674   if( pfsParDerivCurElem( u, v, xdu, ydu, zdu, xdv, ydv, zdv, xdw, ydw, zdw ) )
04675   {
04676    return( 1 );
04677   }
04678  }
04679 
04680  return( 0 );
04681 }
04682 
04683 /*============================ pfsREval ============================*/
04684 
04685 int pfsREval( double u, double v, double *x, double *y, double *z )
04686 {
04687  PFSGeoSurfPar p;
04688  double umin, vmin, umax, vmax;
04689  double tol = 1e-3;
04690  int itr;
04691 
04692  if(pfs == NULL)
04693   return( 0 );
04694 
04695 /* In case given point is outside of surface parametric borders,
04696  * reject point.  If it is close to the boundary, update the
04697  * parametric coordinates to the coordinates of the closest point.
04698   */
04699  p.u = u;
04700  p.v = v;
04701 
04702  if( (! pfsIsParPtInside( &p )) && (! pfsIsParPtOnBound( &p )) )
04703  {
04704   return( 0 );
04705  }
04706  u = p.u;
04707  v = p.v;
04708 
04709  umin = u;
04710  vmin = v;
04711  umax = u;
04712  vmax = v;
04713 
04714  umin -= tol;
04715  vmin -= tol;
04716  umax += tol;
04717  vmax += tol;
04718 
04719  for(itr  = pfsRItrFirstParElem(umin, umax, vmin, vmax);
04720      itr != PFS_ITERATION_END;
04721      itr  = pfsRItrNextParElem(umin, umax, vmin, vmax))
04722  {
04723   if( pfs3dPntCurElem( u, v, x, y, z ) )
04724   {
04725    return( 1 );
04726   }
04727  }
04728 
04729  return( 0 );
04730 }
04731 
04732 /*===========================  pfsShot  ===========================*/
04751 int pfsRShot( void *init_elem, double x0, double y0, double z0,
04752              double u_shot, double v_shot, double len,
04753              void **end_elem, double *x1, double *y1, double *z1 )
04754 {
04755  int ni, nj;     
04756  int type;
04757  double u0, v0;  /* coord paramétrica da posição inicial do tiro */
04758  double u1, v1;  /* coord paramétrica da posição final do tiro   */
04759  double u_aux, v_aux;
04760  PFSGeoPoint p0, p1; /* posição inicial e final, respect.     */
04761  void *init_elem_bck = init_elem;
04762  int  status;
04763  int  in;
04764  
04765  if( init_elem == NULL )
04766  {
04767   printf( "\nERRO: Shot nao pode ter elemento inicial nulo\n" ); 
04768   return( 0 );
04769  }
04770  if( len < TOLER )
04771  {
04772   *x1 = x0;
04773   *y1 = y0;
04774   *z1 = z0;
04775   *end_elem = init_elem;
04776   return( 1 );
04777  }
04778 
04779 /* atualiza o elemento corrente para q ele seja o elemento inicial
04780  */
04781   pfsRSetCurrElem( (PfsElem *)init_elem );
04782 
04783 /* consulta a coordenada paramétrica da posição inicial do tiro 
04784  */
04785  in = pfsParPntCurElemAttract( &x0, &y0, &z0, &u0, &v0 );
04786 
04787 /* Verifica se o ponto está muito próximo a um nó ou aresta e, caso
04788  * positivo, atrai o pto para a posição do nó ou da sua projeção 
04789  * na aresta. Neste caso, considera-se o triangulo inicial, que é 
04790  * dado por init_elem, desconhecido para que a busca seja feita em
04791  * todos os triângulos adjacentes ao nó ou aresta para onde o pto 
04792  * foi atraido.
04793  */
04794  u_aux = u0;
04795  v_aux = v0;
04796  if( pfsChkProxElemEdge( (PfsElem *)init_elem, &u_aux, &v_aux, &type, &ni, &nj ) )
04797  {
04798   /* atualiza a direção do tiro, considerando a nova posição do pt atraído */
04799   u_shot = (u0 + u_shot) - u_aux;
04800   v_shot = (v0 + v_shot) - v_aux;
04801 
04802   u0 = u_aux;
04803   v0 = v_aux;
04804 
04805  /* atualiza a coord cartesiana do pto, considerando sua nova posição */
04806   pfs3dPntCurElem( u0, v0, &x0, &y0, &z0 ); 
04807   init_elem = NULL;
04808  }
04809  else
04810  {
04811   if( in ) 
04812    type = FACE;
04813   else
04814   {
04815    /* pega um nó do loop por onde o tiro saiu */
04816    PfsElem *elem = (PfsElem *)init_elem;
04817    int i;
04818 
04819    status = 0;
04820    for( i=0; i<3; i++ )
04821    {
04822     if( pfs->nodelist[elem->inc[i]].type == NODE_BOUNDARY )
04823     { 
04824      ni = elem->inc[i];
04825      type = LOOP;
04826      type |= FREE_FACE;
04827      status = 1;
04828      break;
04829     }
04830    }
04831    if( !status ) 
04832    {
04833     printf("\nERRO: %d Não foi encontrado o nó  do loop por onde o tiro saiu.\n", pfs_node);
04834     return( 0 );
04835    }
04836   }     
04837  }
04838 
04839  p0.x = x0;
04840  p0.y = y0;
04841  p0.z = z0;
04842  status = pfsShotSolve( (PfsElem *)init_elem, u0, v0, p0, u_shot, v_shot, 
04843                         (PfsElem **)end_elem, &u1, &v1, &p1, &type, &ni, &nj, 
04844                         &len );
04845  
04846  if( status )
04847  {
04848   *x1 = p1.x;
04849   *y1 = p1.y;
04850   *z1 = p1.z;
04851   
04852   if( *end_elem == NULL )
04853    *end_elem = init_elem_bck;
04854 
04855   return( 1 );
04856  }
04857  return( 0 );
04858 }
04859 

Generated on Tue Oct 23 11:23:30 2007 for Relax by  doxygen 1.5.3