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 <assert.h>
00046 #include <climits>
00047 
00048 #include "VRender.h"
00049 #include "Primitive.h"
00050 #include "PrimitivePositioning.h"
00051 #include "AxisAlignedBox.h"
00052 #include "SortMethod.h"
00053 #include "Vector2.h"
00054 
00055 using namespace std ;
00056 using namespace vrender ;
00057 
00058 
00059 
00060 namespace vrender
00061 {
00062 class TopologicalSortUtils
00063 {
00064         public:
00065                 static void buildPrecedenceGraph(vector<PtrPrimitive>& primitive_tab, vector< vector<int> >& precedence_graph) ;
00066 
00067                 static void recursFindNeighbors(        const vector<PtrPrimitive>& primitive_tab,
00068                                                                                                         const vector<int>& pindices,
00069                                                                                                         vector< vector<int> >& precedence_graph,
00070                                                                                                         const AxisAlignedBox_xy&,int) ;
00071 
00072                 static void checkAndAddEdgeToGraph(int a,int b,vector< vector<int> >& precedence_graph) ;
00073                 static void suppressPrecedence(int a,int b,vector< vector<int> >& precedence_graph) ;
00074 
00075                 static void recursTopologicalSort(vector< vector<int> >& precedence_graph,
00076                                                                                                          vector<PtrPrimitive>& primitive_tab,
00077                                                                                                          vector<bool>& alread_rendered,
00078                                                                                                          vector<bool>& alread_visited,
00079                                                                                                          vector<PtrPrimitive>&,int,int&,
00080                                                                                                          VRenderParams& vparams,
00081                                                                                                          int info_cnt,int& nbrendered) ;
00082 
00083                 static void recursTopologicalSort(vector< vector<int> >& precedence_graph,
00084                                                                                                          vector<PtrPrimitive>& primitive_tab,
00085                                                                                                          vector<bool>& alread_rendered,
00086                                                                                                          vector<bool>& alread_visited,
00087                                                                                                          vector<PtrPrimitive>&,int,
00088                                                                                                          vector<int>& ancestors,
00089                                                                                                          int&, int&,
00090                                                                                                          VRenderParams& vparams,
00091                                                                                                          int info_cnt,int& nbrendered) ;
00092 
00093                 static void topologicalSort(    vector< vector<int> >& precedence_graph,
00094                                                                                                 vector<PtrPrimitive>& primitive_tab,
00095                                                                                                 VRenderParams&) ;
00096 
00097                 static void topologicalSortBreakCycles(vector< vector<int> >& precedence_graph,
00098                                                                                                                         vector<PtrPrimitive>& primitive_tab,
00099                                                                                                                         VRenderParams&) ;
00100 
00101 #ifdef DEBUG_TS
00102                 static void printPrecedenceGraph(const vector< vector<int> >& precedence_graph,
00103                                                                                                         const vector<PtrPrimitive>& primitive_tab) ;
00104 #endif
00105 };
00106 
00107 TopologicalSortMethod::TopologicalSortMethod()
00108 {
00109         _break_cycles = false ;
00110 }
00111 
00112 void TopologicalSortMethod::sortPrimitives(vector<PtrPrimitive>& primitive_tab,VRenderParams& vparams)
00113 {
00114         
00115 
00116 #ifdef DEBUG_TS
00117         cout << "Computing precedence graph." << endl ;
00118         cout << "Old order: " ;
00119         for(unsigned int i=0;i<primitive_tab.size();++i) cout << (void *)(primitive_tab[i]) << " " ;
00120         cout << endl ;
00121 #endif
00122         vector< vector<int> > precedence_graph(primitive_tab.size());
00123         TopologicalSortUtils::buildPrecedenceGraph(primitive_tab,precedence_graph) ;
00124 
00125 #ifdef DEBUG_TS
00126         TopologicalSortUtils::printPrecedenceGraph(precedence_graph,primitive_tab) ;
00127 #endif
00128         
00129 
00130 #ifdef DEBUG_TS
00131         cout << "Sorting." << endl ;
00132 #endif
00133 
00134         if(_break_cycles)
00135                 TopologicalSortUtils::topologicalSortBreakCycles(precedence_graph, primitive_tab,vparams) ;
00136         else
00137                 TopologicalSortUtils::topologicalSort(precedence_graph, primitive_tab,vparams) ;
00138 
00139 #ifdef DEBUG_TS
00140         cout << "New order: " ;
00141         for(unsigned int i=0;i<primitive_tab.size();++i) cout << (void *)(primitive_tab[i]) << " " ;
00142         cout << endl ;
00143 #endif
00144 }
00145 
00146 #ifdef DEBUG_TS
00147 void TopologicalSortUtils::printPrecedenceGraph(const vector< vector<int> >& precedence_graph,
00148                                                                                                                                 const vector<PtrPrimitive>& primitive_tab)
00149 {
00150         for(unsigned int i=0;i<precedence_graph.size();++i)
00151         {
00152                 cout << i << " (" << primitive_tab[i]->nbVertices() << ") : " ;
00153                 for(unsigned int j=0;j<precedence_graph[i].size();++j)
00154                         cout << precedence_graph[i][j] << " " ;
00155 
00156                 cout << endl ;
00157         }
00158 }
00159 #endif
00160 
00161 void TopologicalSortUtils::buildPrecedenceGraph(vector<PtrPrimitive>& primitive_tab,
00162                                                                                                                                 vector< vector<int> >& precedence_graph)
00163 {
00164         
00165         
00166         
00167         
00168         
00169         
00170         
00171 
00172         
00173 
00174         AxisAlignedBox_xy BBox ;
00175 
00176         for(unsigned int i=0;i<primitive_tab.size();++i)
00177         {
00178                 BBox.include(Vector2(primitive_tab[i]->bbox().mini().x(),primitive_tab[i]->bbox().mini().y())) ;
00179                 BBox.include(Vector2(primitive_tab[i]->bbox().maxi().x(),primitive_tab[i]->bbox().maxi().y())) ;
00180         }
00181 
00182         
00183 
00184         vector<int> pindices(primitive_tab.size()) ;
00185         for(unsigned int j=0;j<pindices.size();++j)
00186                 pindices[j] = j ;
00187 
00188         recursFindNeighbors(primitive_tab, pindices, precedence_graph, BBox,0) ;
00189 }
00190 
00191 void TopologicalSortUtils::recursFindNeighbors(const vector<PtrPrimitive>& primitive_tab,
00192                                                                                                                                 const vector<int>& pindices,
00193                                                                                                                                 vector< vector<int> >& precedence_graph,
00194                                                                                                                                 const AxisAlignedBox_xy& bbox,
00195                                                                                                                                 int depth)
00196 {
00197         static const unsigned int MAX_PRIMITIVES_IN_CELL = 5 ;
00198 
00199         
00200         
00201 
00202         if(primitive_tab.size() > MAX_PRIMITIVES_IN_CELL)
00203         {
00204                 vector<int> p_indices_min_min ;
00205                 vector<int> p_indices_min_max ;
00206                 vector<int> p_indices_max_min ;
00207                 vector<int> p_indices_max_max ;
00208 
00209                 double xmin = bbox.mini().x() ;
00210                 double ymin = bbox.mini().y() ;
00211                 double xmax = bbox.maxi().x() ;
00212                 double ymax = bbox.maxi().y() ;
00213 
00214                 double xMean = 0.5*(xmin+xmax) ;
00215                 double yMean = 0.5*(ymin+ymax) ;
00216 
00217                 for(unsigned int i=0;i<pindices.size();++i)
00218                 {
00219                         bool left  = primitive_tab[pindices[i]]->bbox().mini().x() <= xMean ;
00220                         bool right = primitive_tab[pindices[i]]->bbox().maxi().x() >= xMean ;
00221                         bool down  = primitive_tab[pindices[i]]->bbox().mini().y() <= yMean ;
00222                         bool up    = primitive_tab[pindices[i]]->bbox().maxi().y() >= yMean ;
00223 
00224                         if(left  && down) p_indices_min_min.push_back(pindices[i]) ;
00225                         if(right && down) p_indices_max_min.push_back(pindices[i]) ;
00226                         if(left  && up  ) p_indices_min_max.push_back(pindices[i]) ;
00227                         if(right && up  ) p_indices_max_max.push_back(pindices[i]) ;
00228                 }
00229 
00230                 
00231 
00232                 if(p_indices_min_min.size() < pindices.size() && p_indices_max_min.size() < pindices.size()
00233                                 && p_indices_min_max.size() < pindices.size() && p_indices_max_max.size() < pindices.size())
00234                 {
00235                         recursFindNeighbors(primitive_tab,p_indices_min_min,precedence_graph,AxisAlignedBox_xy(Vector2(xmin,xMean),Vector2(ymin,yMean)),depth+1) ;
00236                         recursFindNeighbors(primitive_tab,p_indices_min_max,precedence_graph,AxisAlignedBox_xy(Vector2(xmin,xMean),Vector2(yMean,ymax)),depth+1) ;
00237                         recursFindNeighbors(primitive_tab,p_indices_max_min,precedence_graph,AxisAlignedBox_xy(Vector2(xMean,xmax),Vector2(ymin,yMean)),depth+1) ;
00238                         recursFindNeighbors(primitive_tab,p_indices_max_max,precedence_graph,AxisAlignedBox_xy(Vector2(xMean,xmax),Vector2(yMean,ymax)),depth+1) ;
00239                         return ;
00240                 }
00241         }
00242 
00243         
00244         
00245 
00246         for(unsigned int i=0;i<pindices.size();++i)
00247                 for(unsigned int j=i+1;j<pindices.size();++j)
00248                 {
00249                         
00250 
00251                         int prp = PrimitivePositioning::computeRelativePosition(        primitive_tab[pindices[i]], primitive_tab[pindices[j]]) ;
00252 
00253                         if(prp & PrimitivePositioning::Upper) checkAndAddEdgeToGraph(pindices[j],pindices[i],precedence_graph) ;
00254                         if(prp & PrimitivePositioning::Lower) checkAndAddEdgeToGraph(pindices[i],pindices[j],precedence_graph) ;
00255                 }
00256 }
00257 
00258 void TopologicalSortUtils::checkAndAddEdgeToGraph(int a,int b,vector< vector<int> >& precedence_graph)
00259 {
00260 #ifdef DEBUG_TS
00261         cout << "Trying to add " << a << " -> " << b << " " ;
00262 #endif
00263         bool found = false ;
00264 
00265         for(unsigned int k=0;k<precedence_graph[a].size() && !found;++k)
00266                 if(precedence_graph[a][k] == b)
00267                         found = true ;
00268 
00269 #ifdef DEBUG_TS
00270         if(found)
00271                 cout << "already" << endl ;
00272         else
00273                 cout << "ok" << endl ;
00274 #endif
00275         if(!found)
00276                 precedence_graph[a].push_back(b) ;
00277 }
00278 
00279 void TopologicalSortUtils::suppressPrecedence(int a,int b,vector< vector<int> >& precedence_graph)
00280 {
00281         vector<int> prec_tab = vector<int>(precedence_graph[a]) ;
00282         bool trouve = false ;
00283 
00284         for(unsigned int k=0;k<prec_tab.size();++k)
00285                 if(prec_tab[k] == b)
00286                 {
00287                         prec_tab[k] = prec_tab[prec_tab.size()-1] ;
00288                         prec_tab.pop_back() ;
00289                 }
00290 
00291         if(!trouve)
00292                 throw runtime_error("Unexpected error in suppressPrecedence") ;
00293 }
00294 
00295 void TopologicalSortUtils::topologicalSort(vector< vector<int> >& precedence_graph,
00296                                                                                                                  vector<PtrPrimitive>& primitive_tab,
00297                                                                                                                  VRenderParams& vparams)
00298 {
00299         vector<PtrPrimitive> new_pr_tab ;
00300         vector<bool> already_visited(primitive_tab.size(),false) ;
00301         vector<bool> already_rendered(primitive_tab.size(),false) ;
00302         int nb_skews = 0 ;
00303 
00304         unsigned int info_cnt = primitive_tab.size()/200 + 1 ;
00305         int nbrendered = 0 ;
00306 
00307         
00308 
00309         for(unsigned int i=0;i<primitive_tab.size();++i)
00310                 if(!already_rendered[i])
00311                         recursTopologicalSort(precedence_graph,primitive_tab,already_rendered,already_visited,new_pr_tab,i,nb_skews,vparams,info_cnt,nbrendered);
00312 
00313 #ifdef DEBUG_TS
00314         if(nb_skews > 0)
00315                 cout << nb_skews << " cycles found." << endl ;
00316         else
00317                 cout << "No cycles found." << endl ;
00318 #endif
00319         primitive_tab = new_pr_tab ;
00320 }
00321 
00322 void TopologicalSortUtils::topologicalSortBreakCycles(vector< vector<int> >& precedence_graph,
00323                                                                                                                                                 vector<PtrPrimitive>& primitive_tab,
00324                                                                                                                                                 VRenderParams& vparams)
00325 {
00326         vector<PtrPrimitive> new_pr_tab ;
00327         vector<bool> already_visited(primitive_tab.size(),false) ;
00328         vector<bool> already_rendered(primitive_tab.size(),false) ;
00329         vector<int> ancestors ;
00330         int nb_skews = 0 ;
00331         int ancestors_backward_index ;
00332 
00333         int info_cnt = primitive_tab.size()/200 + 1 ;
00334         int nbrendered = 0 ;
00335 
00336         
00337 
00338         for(unsigned int i=0;i<primitive_tab.size();++i)
00339                 if(!already_rendered[i])
00340                         recursTopologicalSort(precedence_graph,primitive_tab,already_rendered,already_visited,
00341                                                                                 new_pr_tab,i,ancestors,ancestors_backward_index,nb_skews,vparams,info_cnt,nbrendered) ;
00342 
00343 #ifdef DEBUG_TS
00344         if(nb_skews > 0)
00345                 cout << nb_skews << " cycles found." << endl ;
00346         else
00347                 cout << "No cycles found." << endl ;
00348 #endif
00349         primitive_tab = new_pr_tab ;
00350 }
00351 
00352 void TopologicalSortUtils::recursTopologicalSort(       vector< vector<int> >& precedence_graph,
00353                                                                                                                                         vector<PtrPrimitive>& primitive_tab,
00354                                                                                                                                         vector<bool>& already_rendered,
00355                                                                                                                                         vector<bool>& already_visited,
00356                                                                                                                                         vector<PtrPrimitive>& new_pr_tab,
00357                                                                                                                                         int indx,
00358                                                                                                                                         int& nb_cycles,
00359                                                                                                                                         VRenderParams& vparams,
00360                                                                                                                                         int info_cnt,int& nbrendered)
00361 {
00362         
00363         
00364 
00365         already_visited[indx] = true ;
00366 
00367         for(unsigned int j=0;j<precedence_graph[indx].size();++j)
00368         {
00369                 
00370                 
00371                 
00372 
00373                 if(!already_visited[precedence_graph[indx][j]])
00374                 {
00375                         if(!already_rendered[precedence_graph[indx][j]])
00376                                 recursTopologicalSort(  precedence_graph,primitive_tab,already_rendered,already_visited,
00377                                                                                                 new_pr_tab,precedence_graph[indx][j],nb_cycles,vparams,info_cnt,nbrendered) ;
00378                 }
00379                 else 
00380                         ++nb_cycles ;
00381         }
00382 
00383         if(!already_rendered[indx])
00384         {
00385                 new_pr_tab.push_back(primitive_tab[indx]) ;
00386 
00387                 if((++nbrendered)%info_cnt==0)
00388                         vparams.progress(nbrendered/(float)primitive_tab.size(), QGLViewer::tr("Topological sort")) ;
00389         }
00390 
00391         already_rendered[indx] = true ;
00392         already_visited[indx] = false ;
00393 }
00394 
00395 void TopologicalSortUtils::recursTopologicalSort(       vector< vector<int> >& precedence_graph,
00396                                                                                                                                         vector<PtrPrimitive>& primitive_tab,
00397                                                                                                                                         vector<bool>& already_rendered,
00398                                                                                                                                         vector<bool>& already_visited,
00399                                                                                                                                         vector<PtrPrimitive>& new_pr_tab,
00400                                                                                                                                         int indx,
00401                                                                                                                                         vector<int>& ancestors,
00402                                                                                                                                         int& ancestors_backward_index,
00403                                                                                                                                         int& nb_cycles,
00404                                                                                                                                         VRenderParams& vparams,
00405                                                                                                                                         int info_cnt,int& nbrendered)
00406 {
00407         
00408         
00409 
00410         already_visited[indx] = true ;
00411         ancestors.push_back(indx) ;
00412 
00413         for(unsigned int j=0;j<precedence_graph[indx].size();++j)
00414         {
00415                 
00416                 
00417                 
00418 
00419                 if(!already_visited[precedence_graph[indx][j]])
00420                 {
00421                         if(!already_rendered[precedence_graph[indx][j]])
00422                         {
00423                                 recursTopologicalSort(  precedence_graph,primitive_tab,already_rendered,already_visited,
00424                                                                                                 new_pr_tab,precedence_graph[indx][j],ancestors,ancestors_backward_index,nb_cycles,vparams,info_cnt,nbrendered) ;
00425 
00426                                 if(ancestors_backward_index != INT_MAX && ancestors.size() > (unsigned int)(ancestors_backward_index+1))
00427                                 {
00428 #ifdef DEBUG_TS
00429                                         cout << "Returning early" << endl ;
00430 #endif
00431                                         already_visited[indx] = false ;
00432                                         ancestors.pop_back() ;
00433                                         return;
00434                                 }
00435                                 if(ancestors_backward_index != INT_MAX) 
00436                                         --j ;
00437                         }
00438                 }
00439                 else
00440                 {
00441                         
00442                         
00443                         
00444                         
00445                         
00446 
00447                         
00448                         ++nb_cycles ;
00449 
00450                         
00451 
00452                         int cycle_beginning_index = -1 ;
00453                         for(int i=(int)(ancestors.size())-1; i >= 0 && cycle_beginning_index < 0;--i)
00454                                 if(ancestors[i] == precedence_graph[indx][j])
00455                                         cycle_beginning_index = i ;
00456 #ifdef DEBUG_TS
00457                         cout << "Unbreaking cycle : " ;
00458                         for(unsigned int i=0;i<ancestors.size();++i)
00459                                 cout << ancestors[i] << " " ;
00460                         cout << precedence_graph[indx][j] << endl ;
00461 #endif
00462 #ifdef DEBUG_TS
00463                         assert(cycle_beginning_index >= 0) ;
00464 #endif
00465                         
00466 
00467                         int split_prim_ancestor_indx = -1 ;
00468                         int split_prim_indx = -1 ;
00469 
00470                         
00471 
00472                         for(unsigned int i2=cycle_beginning_index;i2<ancestors.size() && split_prim_ancestor_indx < 0;++i2)
00473                                 if(primitive_tab[ancestors[i2]]->nbVertices() > 2)
00474                                 {
00475                                         split_prim_ancestor_indx = i2 ;
00476                                         split_prim_indx = ancestors[i2] ;
00477                                 }
00478 
00479 #ifdef DEBUG_TS
00480                         cout << "Split primitive index = " << split_prim_ancestor_indx << "(primitive = " << split_prim_indx << ")" << endl ;
00481 #endif
00482                         if(split_prim_indx < 0) 
00483                                 continue ;
00484 
00485                         
00486 
00487                         const Polygone *P = dynamic_cast<const Polygone *>(primitive_tab[split_prim_indx]) ;
00488                         const NVector3& normal = NVector3(P->normal()) ;
00489                         double c(P->c()) ;
00490                         ancestors.push_back(precedence_graph[indx][j]) ;                                
00491                         ancestors.push_back(ancestors[cycle_beginning_index+1]) ;       
00492                         bool cycle_broken = false ;
00493 
00494                         for(unsigned int i3=cycle_beginning_index+1;i3<ancestors.size()-1 && !cycle_broken;++i3)
00495                                 if(ancestors[i3] != split_prim_indx)
00496                                 {
00497                                         bool prim_lower_ante_contains_im1 = false ;
00498                                         bool prim_upper_ante_contains_im1 = false ;
00499                                         bool prim_lower_prec_contains_ip1 = false ;
00500                                         bool prim_upper_prec_contains_ip1 = false ;
00501 
00502                                         Primitive *prim_upper = NULL ;
00503                                         Primitive *prim_lower = NULL ;
00504 
00505                                         PrimitivePositioning::splitPrimitive(primitive_tab[ancestors[i3]],normal,c,prim_upper,prim_lower) ;
00506 
00507                                         if(prim_upper == NULL || prim_lower == NULL)
00508                                                 continue ;
00509 #ifdef DEBUG_TS
00510                                         cout << "Splitted primitive " << ancestors[i3] << endl ;
00511 #endif
00512 
00513                                         vector<int> prim_upper_prec ;
00514                                         vector<int> prim_lower_prec ;
00515 
00516                                         vector<int> old_prec = vector<int>(precedence_graph[ancestors[i3]]) ;
00517 
00518                                         unsigned int upper_indx = precedence_graph.size() ;
00519                                         int lower_indx = ancestors[i3] ;
00520 
00521                                         
00522 
00523                                         for(unsigned int k=0;k<old_prec.size();++k)
00524                                         {
00525                                                 int prp1 = PrimitivePositioning::computeRelativePosition(prim_upper,primitive_tab[old_prec[k]]) ;
00526 #ifdef DEBUG_TS
00527                                                 cout << "Compariing " << upper_indx << " and " << old_prec[k] << ": " ;
00528 #endif
00529                                                 
00530                                                 
00531 
00532                                                 if(prp1 & PrimitivePositioning::Lower)
00533                                                 {
00534 #ifdef DEBUG_TS
00535                                                         cout << " > " << endl ;
00536 #endif
00537                                                         prim_upper_prec.push_back(old_prec[k]) ;
00538 
00539                                                         if(old_prec[k] == ancestors[i3+1])
00540                                                                 prim_upper_prec_contains_ip1 = true ;
00541                                                 }
00542 #ifdef DEBUG_TS
00543                                                 else
00544                                                         cout << " I " << endl ;
00545 #endif
00546 
00547                                                 int prp2 = PrimitivePositioning::computeRelativePosition(prim_lower,primitive_tab[old_prec[k]]) ;
00548 #ifdef DEBUG_TS
00549                                                 cout << "Compariing " << lower_indx << " and " << old_prec[k] << ": " ;
00550 #endif
00551                                                 if(prp2 & PrimitivePositioning::Lower)
00552                                                 {
00553 #ifdef DEBUG_TS
00554                                                         cout << " > " << endl ;
00555 #endif
00556                                                         prim_lower_prec.push_back(old_prec[k]) ;
00557 
00558                                                         if(old_prec[k] == ancestors[i3+1])
00559                                                                 prim_lower_prec_contains_ip1 = true ;
00560                                                 }
00561 #ifdef DEBUG_TS
00562                                                 else
00563                                                         cout << " I " << endl ;
00564 #endif
00565                                         }
00566 
00567                                         
00568                                         
00569                                         
00570                                         
00571                                         
00572 
00573                                         for(unsigned int l=0;l<precedence_graph.size();++l)
00574                                                 if(l != (unsigned int)lower_indx)
00575                                                         for(int k=0;k<(int)precedence_graph[l].size();++k)
00576                                                                 if(precedence_graph[l][k] == ancestors[i3])
00577                                                                 {
00578                                                                         int prp1 = PrimitivePositioning::computeRelativePosition(prim_upper,primitive_tab[l]) ;
00579 
00580                                                                         
00581                                                                         
00582 
00583                                                                         if(prp1 & PrimitivePositioning::Upper)
00584                                                                         {
00585                                                                                 
00586 
00587                                                                                 precedence_graph[l].push_back(upper_indx) ;
00588 
00589                                                                                 if(l == (unsigned int)ancestors[i3-1])
00590                                                                                         prim_upper_ante_contains_im1 = true ;
00591                                                                         }
00592                                                                         
00593                                                                         
00594 
00595                                                                         int prp2 = PrimitivePositioning::computeRelativePosition(prim_lower,primitive_tab[l]) ;
00596 #ifdef DEBUG_TS
00597                                                                         cout << "Compariing " << l << " and " << lower_indx  << ": " ;
00598 #endif
00599                                                                         if(prp2 & PrimitivePositioning::Upper)
00600                                                                         {
00601 #ifdef DEBUG_TS
00602                                                                                 cout << " > " << endl ;
00603 #endif
00604                                                                                 if(l == (unsigned int)ancestors[i3-1])                                           
00605                                                                                         prim_lower_ante_contains_im1 = true ;
00606                                                                         }
00607                                                                         else
00608                                                                         {
00609 #ifdef DEBUG_TS
00610                                                                                 cout << " I " << endl ;
00611 #endif
00612                                                                                 
00613 
00614                                                                                 precedence_graph[l][k] = precedence_graph[l][precedence_graph[l].size()-1] ;
00615                                                                                 precedence_graph[l].pop_back() ;
00616                                                                                 --k ;
00617                                                                         }
00618 
00619                                                                         break ; 
00620                                                                 }
00621 
00622                                         
00623 
00624                                         primitive_tab.push_back(prim_upper) ;
00625                                         delete primitive_tab[lower_indx] ;
00626                                         primitive_tab[lower_indx] = prim_lower ;
00627 
00628                                         
00629 
00630                                         precedence_graph.push_back(prim_upper_prec) ;
00631                                         precedence_graph[lower_indx] = prim_lower_prec ;
00632 
00633                                         
00634                                         already_visited.push_back(false) ;
00635                                         already_rendered.push_back(false) ;
00636 #ifdef DEBUG_TS
00637                                         cout << "New precedence graph: " << endl ;
00638                                         printPrecedenceGraph(precedence_graph,primitive_tab) ;
00639 #endif
00640                                         
00641                                         
00642                                         
00643                                         
00644 
00645                                         if(( !(prim_lower_ante_contains_im1 && prim_lower_prec_contains_ip1))
00646                                           &&(!(prim_upper_ante_contains_im1 && prim_upper_prec_contains_ip1)))
00647                                                 cycle_broken = true ;
00648                                 }
00649 
00650                         ancestors.pop_back() ;
00651                         ancestors.pop_back() ;
00652 
00653                         
00654 
00655                         if(cycle_broken)
00656                         {
00657                                 ancestors_backward_index = cycle_beginning_index ;
00658 #ifdef DEBUG_TS
00659                                 cout << "Cycle broken. Jumping back to rank " << ancestors_backward_index << endl ;
00660 #endif
00661                                 already_visited[indx] = false ;
00662                                 ancestors.pop_back() ;
00663                                 return;
00664                         }
00665 #ifdef DEBUG_TS
00666                         else
00667                                 cout << "Cycle could not be broken !!" << endl ;
00668 #endif
00669                 }
00670         }
00671 
00672         if(!already_rendered[indx])
00673         {
00674 #ifdef DEBUG_TS
00675                 cout << "Returning ok. Rendered primitive " << indx << endl ;
00676 #endif
00677                 new_pr_tab.push_back(primitive_tab[indx]) ;
00678 
00679                 if((++nbrendered)%info_cnt==0)
00680                         vparams.progress(nbrendered/(float)primitive_tab.size(), QGLViewer::tr("Advanced topological sort")) ;
00681         }
00682 
00683         already_rendered[indx] = true ;
00684         ancestors_backward_index = INT_MAX ;
00685         already_visited[indx] = false ;
00686         ancestors.pop_back() ;
00687 }
00688 }