Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 
00045 #include "VRender.h"
00046 #include "Primitive.h"
00047 #include "SortMethod.h"
00048 #include "math.h" 
00049 
00050 using namespace vrender;
00051 using namespace std;
00052 
00053 double EGALITY_EPS              = 0.0001;
00054 double LINE_EGALITY_EPS = 0.0001;
00055 
00056 typedef enum { BSP_CROSS_PLANE, BSP_UPPER, BSP_LOWER } BSPPosition;
00057 
00058 class BSPNode;
00059 
00060 class BSPTree
00061 {
00062         public:
00063                 BSPTree();
00064                 ~BSPTree();
00065 
00066                 void insert(Polygone *);
00067                 void insert(Segment *);
00068                 void insert(Point *);
00069 
00070                 void recursFillPrimitiveArray(vector<PtrPrimitive>&) const;
00071         private:
00072                 BSPNode *_root;
00073                 vector<Segment *> _segments;    
00074                 vector<Point *> _points;
00075 };
00076 
00077 void BSPSortMethod::sortPrimitives(std::vector<PtrPrimitive>& primitive_tab,VRenderParams& vparams)
00078 {
00079         
00080 
00081         BSPTree tree;
00082         Polygone *P;
00083 
00084         unsigned int N = primitive_tab.size()/200 +1;
00085         int nbinserted = 0;
00086 
00087         vector<PtrPrimitive> segments_and_points;       
00088                                                                                                                                 
00089         for(unsigned int i=0;i<primitive_tab.size();++i,++nbinserted)
00090         {
00091                 if((P = dynamic_cast<Polygone *>(primitive_tab[i])) != NULL)
00092                         tree.insert(P);
00093                 else
00094                         segments_and_points.push_back(primitive_tab[i]);
00095 
00096                 if(nbinserted%N==0)
00097                         vparams.progress(nbinserted/(float)primitive_tab.size(), QGLViewer::tr("BSP Construction"));
00098         }
00099 
00100         
00101 
00102         Segment *S;
00103         Point *p;
00104 
00105         for(unsigned int j=0;j<segments_and_points.size();++j,++nbinserted)
00106         {
00107                 if((S = dynamic_cast<Segment *>(segments_and_points[j])) != NULL)
00108                         tree.insert(S);
00109                 else if((p = dynamic_cast<Point *>(segments_and_points[j])) != NULL)
00110                         tree.insert(p);
00111 
00112                 if(nbinserted%N==0)
00113                         vparams.progress(nbinserted/(float)primitive_tab.size(), QGLViewer::tr("BSP Construction"));
00114         }
00115 
00116         
00117 
00118         primitive_tab.resize(0);
00119         tree.recursFillPrimitiveArray(primitive_tab);
00120 }
00121 
00123 
00124 class BSPNode
00125 {
00126         public:
00127                 BSPNode(Polygone *);
00128                 ~BSPNode();
00129 
00130                 void recursFillPrimitiveArray(vector<PtrPrimitive>&) const;
00131 
00132                 void insert(Polygone *);
00133                 void insert(Segment *);
00134                 void insert(Point *);
00135 
00136         private:
00137                 double a,b,c,d;
00138 
00139                 BSPNode *fils_moins;
00140                 BSPNode *fils_plus;
00141 
00142                 vector<Segment *> seg_plus;
00143                 vector<Segment *> seg_moins;
00144 
00145                 vector<Point *> pts_plus;
00146                 vector<Point *> pts_moins;
00147 
00148                 Polygone *polygone;
00149 
00150                 void Classify(Polygone *, Polygone * &, Polygone * &);
00151                 void Classify(Segment *, Segment * &, Segment * &);
00152                 int  Classify(Point *);
00153 
00154                 void initEquation(const Polygone *P,double & a, double & b, double & c, double & d);
00155 };
00156 
00157 BSPTree::BSPTree()
00158 {
00159         _root = NULL;
00160 }
00161 
00162 BSPTree::~BSPTree()
00163 {
00164         delete _root;
00165 }
00166 
00167 void BSPTree::insert(Point *P)  { if(_root == NULL) _points.push_back(P)        ; else _root->insert(P); }
00168 void BSPTree::insert(Segment *S) { if(_root == NULL) _segments.push_back(S); else _root->insert(S); }
00169 void BSPTree::insert(Polygone *P){ if(_root == NULL) _root = new BSPNode(P); else _root->insert(P); }
00170 
00171 void BSPTree::recursFillPrimitiveArray(vector<PtrPrimitive>& tab) const
00172 {
00173         if(_root != NULL) _root->recursFillPrimitiveArray(tab);
00174 
00175         for(unsigned int i=0;i<_points.size();++i) tab.push_back(_points[i]);
00176         for(unsigned int j=0;j<_segments.size();++j) tab.push_back(_segments[j]);
00177 }
00178 
00179 
00180 
00181 BSPNode::~BSPNode()
00182 {
00183         delete fils_moins;
00184         delete fils_plus;
00185 }
00186 
00187 int BSPNode::Classify(Point *P)
00188 {
00189   double Z = P->sommet3DColor(0).x() * a + P->sommet3DColor(0).y() * b + P->sommet3DColor(0).z() * c - d;
00190 
00191   if(Z > EGALITY_EPS)
00192     return 1;
00193   else
00194     return -1;
00195 }
00196 
00197 void BSPNode::Classify(Segment *S, Segment * & moins_, Segment * & plus_)
00198 {
00199         double Z1 = S->sommet3DColor(0).x() * a + S->sommet3DColor(0).y() * b + S->sommet3DColor(0).z() * c - d;
00200         double Z2 = S->sommet3DColor(1).x() * a + S->sommet3DColor(1).y() * b + S->sommet3DColor(1).z() * c - d;
00201 
00202         int s1, s2;
00203 
00204         if(Z1 < -LINE_EGALITY_EPS)
00205                 s1 = -1;
00206         else if(Z1 > EGALITY_EPS)
00207                 s1 = 1;
00208         else
00209                 s1 = 0;
00210 
00211         if(Z2 < -LINE_EGALITY_EPS)
00212                 s2 = -1;
00213         else if(Z2 > EGALITY_EPS)
00214                 s2 = 1;
00215         else
00216                 s2 = 0;
00217 
00218         if(s1 == -s2)
00219         {
00220                 if(s1 == 0)
00221                 {
00222                         moins_ = S;
00223                         plus_  = NULL;
00224                         return;
00225                 }
00226                 else
00227                 {
00228                         double t = fabs(Z1/(Z2 - Z1));
00229 
00230                         if((t < 0.0)||(t > 1.0))
00231                         {
00232                                 if(t > 1.0) t = 0.999;
00233                                 if(t < 0.0) t = 0.001;
00234                         }
00235 
00236                         Feedback3DColor newVertex((1-t)*S->sommet3DColor(0) + t*S->sommet3DColor(1));
00237 
00238                         if(s1 > 0)
00239                         {
00240                                 plus_  = new Segment(S->sommet3DColor(0), newVertex);
00241                                 moins_ = new Segment(newVertex, S->sommet3DColor(1));
00242                         }
00243                         else
00244                         {
00245                                 plus_  = new Segment(newVertex, S->sommet3DColor(1));
00246                                 moins_ = new Segment(S->sommet3DColor(0), newVertex);
00247                         }
00248 
00249                         delete S;
00250                         return;
00251                 }
00252         }
00253         else if(s1 == s2)
00254         {
00255                 if(s1 == -1)
00256                 {
00257                         moins_ = S;
00258                         plus_ = NULL;
00259                         return;
00260                 }
00261                 else
00262                 {
00263                         moins_ = NULL;
00264                         plus_  = S;
00265                         return;
00266                 }
00267         }
00268         else if(s1 == 0)
00269         {
00270                 if(s2 > 0)
00271                 {
00272                         moins_ = NULL;
00273                         plus_  = S;
00274                         return;
00275                 }
00276                 else
00277                 {
00278                         moins_ = S;
00279                         plus_  = NULL;
00280                         return;
00281                 }
00282         }
00283         else if(s2 == 0)
00284         {
00285                 if(s1 > 0)
00286                 {
00287                         moins_ = NULL;
00288                         plus_  = S;
00289                         return;
00290                 }
00291                 else
00292                 {
00293                         moins_ = S;
00294                         plus_  = NULL;
00295                         return;
00296                 }
00297         }
00298         
00299                 
00300 }
00301 
00302 void BSPNode::Classify(Polygone *P, Polygone * & moins_, Polygone * & plus_)
00303 {
00304         static int Signs[100];
00305         static double Zvals[100];
00306 
00307         moins_ = NULL;
00308         plus_ = NULL;
00309 
00310         if(P == NULL)
00311         {
00312                 
00313                 return;
00314         }
00315 
00316         int n = P->nbVertices();
00317 
00318         int Smin = 1;
00319         int Smax = -1;
00320 
00321         
00322 
00323         for(int i=0;i<n;i++)
00324         {
00325                 double Z = P->vertex(i).x() * a + P->vertex(i).y() * b + P->vertex(i).z() * c - d;
00326 
00327                 if(Z < -EGALITY_EPS)
00328                         Signs[i] = -1;
00329                 else if(Z > EGALITY_EPS)
00330                         Signs[i] = 1;
00331                 else
00332                         Signs[i] = 0;
00333 
00334                 Zvals[i] = Z;
00335 
00336                 if(Smin > Signs[i]) Smin = Signs[i];
00337                 if(Smax < Signs[i]) Smax = Signs[i];
00338         }
00339 
00340         
00341 
00342         if((Smin == 0)&&(Smax == 0))
00343         {
00344                 moins_ = P;
00345                 plus_  = NULL;
00346                 return;
00347         }
00348 
00349         
00350 
00351         if(Smin == 1)
00352         {
00353                 plus_  = P;
00354                 moins_ = NULL;
00355                 return;
00356         }
00357 
00358         
00359 
00360         if(Smax == -1)
00361         {
00362                 plus_ = NULL;
00363                 moins_ = P;
00364                 return;
00365         }
00366 
00367         if((Smin == -1)&&(Smax == 0))
00368         {
00369                 plus_ = NULL;
00370                 moins_ = P;
00371                 return;
00372         }
00373 
00374         if((Smin == 0)&&(Smax == 1))
00375         {
00376                 plus_ = P;
00377                 moins_ = NULL;
00378                 return;
00379         }
00380 
00381         
00382 
00383         vector<Feedback3DColor> Ps;
00384         vector<Feedback3DColor> Ms;
00385 
00386         
00387 
00388         int nZero = 0;
00389         int nconsZero = 0;
00390 
00391         for(int j=0;j<n;j++)
00392         {
00393                 if(Signs[j] == 0)
00394                 {
00395                         nZero++;
00396 
00397                         if(Signs[(j+1)%n] == 0)
00398                                 nconsZero++;
00399                 }
00400         }
00401 
00402         if((nZero > 2)||(nconsZero > 0))
00403         {
00404                 
00405 
00406                 moins_ = P;
00407                 plus_  = NULL;
00408                 return;
00409         }
00410 
00411         int dep=0;
00412 
00413         while(Signs[dep] == 0) dep++;
00414 
00415         int prev_sign = Signs[dep];
00416 
00417         for(int k=1;k<=n;k++)
00418         {
00419                 int sign = Signs[(k+dep)%n];
00420 
00421                 if(sign == prev_sign)
00422                 {
00423                         if(sign == 1)
00424                                 Ps.push_back(P->sommet3DColor(k+dep));
00425 
00426                         if(sign == -1)
00427                                 Ms.push_back(P->sommet3DColor(k+dep));
00428                 }
00429                 else if(sign == -prev_sign)
00430                 {
00431                         
00432                         
00433 
00434                         double Z1 = Zvals[(k+dep-1)%n];
00435                         double Z2 = Zvals[(k+dep)%n];
00436 
00437                         double t = fabs(Z1/(Z2 - Z1));
00438 
00439                         if((t < 0.0)||(t > 1.0))
00440                         {
00441                                 if(t > 1.0) t = 0.999;
00442                                 if(t < 0.0) t = 0.001;
00443                         }
00444 
00445                         Feedback3DColor newVertex((1-t)*P->sommet3DColor(k+dep-1) + t*P->sommet3DColor(k+dep));
00446 
00447                         Ps.push_back(newVertex);
00448                         Ms.push_back(newVertex);
00449 
00450                         if(sign == 1)
00451                                 Ps.push_back(P->sommet3DColor(k+dep));
00452 
00453                         if(sign == -1)
00454                                 Ms.push_back(P->sommet3DColor(k+dep));
00455 
00456                         prev_sign = sign;
00457                 } 
00458                 else
00459                 {
00460                         Feedback3DColor newVertex = P->sommet3DColor(k+dep);
00461 
00462                         Ps.push_back(newVertex);
00463                         Ms.push_back(newVertex);
00464 
00465                         prev_sign = -prev_sign;
00466                 }
00467         }
00468 
00469         
00470                 
00471 
00472         
00473                 
00474 
00475         
00476                 
00477 
00478         
00479 
00480         
00481         
00482 
00483         plus_  = new Polygone(Ps);
00484         moins_ = new Polygone(Ms);
00485 
00486         delete  P;
00487 }
00488 
00489 void BSPNode::insert(Polygone *P)
00490 {
00491         Polygone *side_plus = NULL, *side_moins = NULL;
00492 
00493         
00494 
00495         Classify(P,side_moins,side_plus);
00496 
00497         
00498 
00499         if(side_plus != NULL) {
00500                 if(fils_plus == NULL)
00501                         fils_plus = new BSPNode(side_plus);
00502                 else
00503                         fils_plus->insert(side_plus);
00504         }
00505         
00506         if(side_moins != NULL) {
00507                 if(fils_moins == NULL)
00508                         fils_moins = new BSPNode(side_moins);
00509                 else
00510                         fils_moins->insert(side_moins);
00511         }
00512 }
00513 
00514 void BSPNode::recursFillPrimitiveArray(vector<PtrPrimitive>& primitive_tab) const
00515 {
00516   if(fils_plus != NULL)
00517     fils_plus->recursFillPrimitiveArray(primitive_tab);
00518 
00519   for(unsigned int i=0;i<seg_plus.size();++i)
00520     primitive_tab.push_back(seg_plus[i]);
00521   for(unsigned int j=0;j<pts_plus.size();++j)
00522     primitive_tab.push_back(pts_plus[j]);
00523 
00524   if(polygone != NULL)
00525     primitive_tab.push_back(polygone);
00526 
00527   if(fils_moins != NULL)
00528     fils_moins->recursFillPrimitiveArray(primitive_tab);
00529 
00530   for(unsigned int i2=0;i2<seg_moins.size();++i2)
00531     primitive_tab.push_back(seg_moins[i2]);
00532   for(unsigned int j2=0;j2<pts_moins.size();++j2)
00533     primitive_tab.push_back(pts_moins[j2]);
00534 }
00535 
00536 void BSPNode::insert(Point *P)
00537 {
00538         int res = Classify(P);
00539 
00540         if(res == -1) {
00541                 if(fils_moins == NULL)
00542                         pts_moins.push_back(P);
00543                 else
00544                         fils_moins->insert(P);
00545         }
00546 
00547         if(res == 1) {
00548                 if(fils_plus == NULL)
00549                         pts_plus.push_back(P);
00550                 else
00551                         fils_plus->insert(P);
00552         }
00553 }
00554 
00555 void BSPNode::insert(Segment *S)
00556 {
00557         Segment *side_plus = NULL, *side_moins = NULL;
00558 
00559         Classify(S,side_moins,side_plus);
00560 
00561         if(side_plus != NULL) {
00562                 if(fils_plus == NULL)
00563                         seg_plus.push_back(side_plus);
00564                 else
00565                         fils_plus->insert(side_plus);
00566         }
00567 
00568         if(side_moins != NULL) {
00569                 if(fils_moins == NULL)
00570                         seg_moins.push_back(side_moins);
00571                 else
00572                         fils_moins->insert(side_moins);
00573         }
00574 }
00575 
00576 BSPNode::BSPNode(Polygone *P)
00577 {
00578   polygone = P;
00579 
00580   initEquation(P,a,b,c,d);
00581 
00582   fils_moins = NULL;
00583   fils_plus  = NULL;
00584 }
00585 
00586 void BSPNode::initEquation(const Polygone *P,double & a, double & b, double & c, double & d)
00587 {
00588         Vector3 n(0.,0.,0.);
00589         unsigned int j = 0;
00590 
00591         while((j < P->nbVertices())&& n.infNorm() <= 0.00001)
00592         {
00593                 n = (P->vertex(j+2) - P->vertex(j+1))^(P->vertex(j) - P->vertex(j+1));
00594                 j++;
00595         }
00596 
00597         if(n.infNorm() <= 0.00001)
00598         {
00599                 unsigned int ind = P->nbVertices();
00600 
00601                 for(unsigned int i=0;i<P->nbVertices();i++)
00602                         if((P->vertex(i+1)-P->vertex(i)).infNorm() > 0.00001)
00603                         {
00604                                 ind = i;
00605                                 i = P->nbVertices();
00606                         }
00607 
00608                 if(ind < P->nbVertices())       
00609                 {
00610                         if((P->vertex(ind+1).x() != P->vertex(ind).x())||(P->vertex(ind+1).y() != P->vertex(ind).y()))
00611                         {
00612                                 n[0] = - P->vertex(ind+1).y() + P->vertex(ind).y();
00613                                 n[1] =   P->vertex(ind+1).x() - P->vertex(ind).x();
00614                                 n[2] =   0;
00615                         }
00616                         else
00617                         {
00618                                 n[0] = - P->vertex(ind+1).z() + P->vertex(ind).z();
00619                                 n[1] =   0;
00620                                 n[2] =   P->vertex(ind+1).x() - P->vertex(ind).x();
00621                         }
00622                 }
00623                 else                            
00624                 {
00625                         n[0] = 1.0;
00626                         n[1] = 0.0;
00627                         n[2] = 0.0;
00628                 }
00629         }
00630 
00631         double D = n.norm();
00632 
00633         if(n[2] < 0.0)
00634                 n /= -D;
00635         else
00636                 n /= D;
00637 
00638         d = n*P->vertex(0);
00639 
00640         a = n[0];
00641         b = n[1];
00642         c = n[2];
00643 }
00644