gim_box_set.h
Go to the documentation of this file.
00001 #ifndef GIM_BOX_SET_H_INCLUDED
00002 #define GIM_BOX_SET_H_INCLUDED
00003 
00007 /*
00008 -----------------------------------------------------------------------------
00009 This source file is part of GIMPACT Library.
00010 
00011 For the latest info, see http://gimpact.sourceforge.net/
00012 
00013 Copyright (c) 2006 Francisco Leon Najera. C.C. 80087371.
00014 email: projectileman@yahoo.com
00015 
00016  This library is free software; you can redistribute it and/or
00017  modify it under the terms of EITHER:
00018    (1) The GNU Lesser General Public License as published by the Free
00019        Software Foundation; either version 2.1 of the License, or (at
00020        your option) any later version. The text of the GNU Lesser
00021        General Public License is included with this library in the
00022        file GIMPACT-LICENSE-LGPL.TXT.
00023    (2) The BSD-style license that is included with this library in
00024        the file GIMPACT-LICENSE-BSD.TXT.
00025    (3) The zlib/libpng license that is included with this library in
00026        the file GIMPACT-LICENSE-ZLIB.TXT.
00027 
00028  This library is distributed in the hope that it will be useful,
00029  but WITHOUT ANY WARRANTY; without even the implied warranty of
00030  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files
00031  GIMPACT-LICENSE-LGPL.TXT, GIMPACT-LICENSE-ZLIB.TXT and GIMPACT-LICENSE-BSD.TXT for more details.
00032 
00033 -----------------------------------------------------------------------------
00034 */
00035 
00036 
00037 #include "gim_array.h"
00038 #include "gim_radixsort.h"
00039 #include "gim_box_collision.h"
00040 #include "gim_tri_collision.h"
00041 
00042 
00043 
00045 struct GIM_PAIR
00046 {
00047     GUINT m_index1;
00048     GUINT m_index2;
00049     GIM_PAIR()
00050     {}
00051 
00052     GIM_PAIR(const GIM_PAIR & p)
00053     {
00054         m_index1 = p.m_index1;
00055         m_index2 = p.m_index2;
00056         }
00057 
00058         GIM_PAIR(GUINT index1, GUINT index2)
00059     {
00060         m_index1 = index1;
00061         m_index2 = index2;
00062         }
00063 };
00064 
00066 class gim_pair_set: public gim_array<GIM_PAIR>
00067 {
00068 public:
00069         gim_pair_set():gim_array<GIM_PAIR>(32)
00070         {
00071         }
00072         inline void push_pair(GUINT index1,GUINT index2)
00073         {
00074                 push_back(GIM_PAIR(index1,index2));
00075         }
00076 
00077         inline void push_pair_inv(GUINT index1,GUINT index2)
00078         {
00079                 push_back(GIM_PAIR(index2,index1));
00080         }
00081 };
00082 
00083 
00085 
00090 class GIM_PRIMITIVE_MANAGER_PROTOTYPE
00091 {
00092 public:
00093 
00094         virtual ~GIM_PRIMITIVE_MANAGER_PROTOTYPE() {}
00096         virtual bool is_trimesh() = 0;
00097         virtual GUINT get_primitive_count() = 0;
00098         virtual void get_primitive_box(GUINT prim_index ,GIM_AABB & primbox) = 0;
00099         virtual void get_primitive_triangle(GUINT prim_index,GIM_TRIANGLE & triangle) = 0;
00100 };
00101 
00102 
00103 struct GIM_AABB_DATA
00104 {
00105         GIM_AABB m_bound;
00106         GUINT m_data;
00107 };
00108 
00110 struct GIM_BOX_TREE_NODE
00111 {
00112         GIM_AABB m_bound;
00113         GUINT m_left;
00114         GUINT m_right;
00115         GUINT m_escapeIndex;
00116         GUINT m_data;
00117 
00118         GIM_BOX_TREE_NODE()
00119         {
00120             m_left = 0;
00121             m_right = 0;
00122             m_escapeIndex = 0;
00123             m_data = 0;
00124         }
00125 
00126         SIMD_FORCE_INLINE bool is_leaf_node() const
00127         {
00128             return  (!m_left && !m_right);
00129         }
00130 };
00131 
00133 class GIM_BOX_TREE
00134 {
00135 protected:
00136         GUINT m_num_nodes;
00137         gim_array<GIM_BOX_TREE_NODE> m_node_array;
00138 protected:
00139         GUINT _sort_and_calc_splitting_index(
00140                 gim_array<GIM_AABB_DATA> & primitive_boxes,
00141                  GUINT startIndex,  GUINT endIndex, GUINT splitAxis);
00142 
00143         GUINT _calc_splitting_axis(gim_array<GIM_AABB_DATA> & primitive_boxes, GUINT startIndex,  GUINT endIndex);
00144 
00145         void _build_sub_tree(gim_array<GIM_AABB_DATA> & primitive_boxes, GUINT startIndex,  GUINT endIndex);
00146 public:
00147         GIM_BOX_TREE()
00148         {
00149                 m_num_nodes = 0;
00150         }
00151 
00154         void build_tree(gim_array<GIM_AABB_DATA> & primitive_boxes);
00155 
00156         SIMD_FORCE_INLINE void clearNodes()
00157         {
00158                 m_node_array.clear();
00159                 m_num_nodes = 0;
00160         }
00161 
00163         SIMD_FORCE_INLINE GUINT getNodeCount() const
00164         {
00165                 return m_num_nodes;
00166         }
00167 
00169         SIMD_FORCE_INLINE bool isLeafNode(GUINT nodeindex) const
00170         {
00171                 return m_node_array[nodeindex].is_leaf_node();
00172         }
00173 
00174         SIMD_FORCE_INLINE GUINT getNodeData(GUINT nodeindex) const
00175         {
00176                 return m_node_array[nodeindex].m_data;
00177         }
00178 
00179         SIMD_FORCE_INLINE void getNodeBound(GUINT nodeindex, GIM_AABB & bound) const
00180         {
00181                 bound = m_node_array[nodeindex].m_bound;
00182         }
00183 
00184         SIMD_FORCE_INLINE void setNodeBound(GUINT nodeindex, const GIM_AABB & bound)
00185         {
00186                 m_node_array[nodeindex].m_bound = bound;
00187         }
00188 
00189         SIMD_FORCE_INLINE GUINT getLeftNodeIndex(GUINT nodeindex)  const
00190         {
00191                 return m_node_array[nodeindex].m_left;
00192         }
00193 
00194         SIMD_FORCE_INLINE GUINT getRightNodeIndex(GUINT nodeindex)  const
00195         {
00196                 return m_node_array[nodeindex].m_right;
00197         }
00198 
00199         SIMD_FORCE_INLINE GUINT getScapeNodeIndex(GUINT nodeindex) const
00200         {
00201                 return m_node_array[nodeindex].m_escapeIndex;
00202         }
00203 
00205 };
00206 
00207 
00209 
00214 template<typename _GIM_PRIMITIVE_MANAGER_PROTOTYPE, typename _GIM_BOX_TREE_PROTOTYPE>
00215 class GIM_BOX_TREE_TEMPLATE_SET
00216 {
00217 protected:
00218         _GIM_PRIMITIVE_MANAGER_PROTOTYPE m_primitive_manager;
00219         _GIM_BOX_TREE_PROTOTYPE m_box_tree;
00220 protected:
00221         //stackless refit
00222         SIMD_FORCE_INLINE void refit()
00223         {
00224                 GUINT nodecount = getNodeCount();
00225                 while(nodecount--)
00226                 {
00227                         if(isLeafNode(nodecount))
00228                         {
00229                                 GIM_AABB leafbox;
00230                                 m_primitive_manager.get_primitive_box(getNodeData(nodecount),leafbox);
00231                                 setNodeBound(nodecount,leafbox);
00232                         }
00233                         else
00234                         {
00235                                 //get left bound
00236                                 GUINT childindex = getLeftNodeIndex(nodecount);
00237                                 GIM_AABB bound;
00238                                 getNodeBound(childindex,bound);
00239                                 //get right bound
00240                                 childindex = getRightNodeIndex(nodecount);
00241                                 GIM_AABB bound2;
00242                                 getNodeBound(childindex,bound2);
00243                                 bound.merge(bound2);
00244 
00245                                 setNodeBound(nodecount,bound);
00246                         }
00247                 }
00248         }
00249 public:
00250 
00251         GIM_BOX_TREE_TEMPLATE_SET()
00252         {
00253         }
00254 
00255         SIMD_FORCE_INLINE GIM_AABB getGlobalBox()  const
00256         {
00257                 GIM_AABB totalbox;
00258                 getNodeBound(0, totalbox);
00259                 return totalbox;
00260         }
00261 
00262         SIMD_FORCE_INLINE void setPrimitiveManager(const _GIM_PRIMITIVE_MANAGER_PROTOTYPE & primitive_manager)
00263         {
00264                 m_primitive_manager = primitive_manager;
00265         }
00266 
00267         const _GIM_PRIMITIVE_MANAGER_PROTOTYPE & getPrimitiveManager() const
00268         {
00269                 return m_primitive_manager;
00270         }
00271 
00272         _GIM_PRIMITIVE_MANAGER_PROTOTYPE & getPrimitiveManager()
00273         {
00274                 return m_primitive_manager;
00275         }
00276 
00279 
00281         SIMD_FORCE_INLINE void update()
00282         {
00283                 refit();
00284         }
00285 
00287         SIMD_FORCE_INLINE void buildSet()
00288         {
00289                 //obtain primitive boxes
00290                 gim_array<GIM_AABB_DATA> primitive_boxes;
00291                 primitive_boxes.resize(m_primitive_manager.get_primitive_count(),false);
00292 
00293                 for (GUINT i = 0;i<primitive_boxes.size() ;i++ )
00294                 {
00295                          m_primitive_manager.get_primitive_box(i,primitive_boxes[i].m_bound);
00296                          primitive_boxes[i].m_data = i;
00297                 }
00298 
00299                 m_box_tree.build_tree(primitive_boxes);
00300         }
00301 
00303         SIMD_FORCE_INLINE bool boxQuery(const GIM_AABB & box, gim_array<GUINT> & collided_results) const
00304         {
00305                 GUINT curIndex = 0;
00306                 GUINT numNodes = getNodeCount();
00307 
00308                 while (curIndex < numNodes)
00309                 {
00310                         GIM_AABB bound;
00311                         getNodeBound(curIndex,bound);
00312 
00313                         //catch bugs in tree data
00314 
00315                         bool aabbOverlap = bound.has_collision(box);
00316                         bool isleafnode = isLeafNode(curIndex);
00317 
00318                         if (isleafnode && aabbOverlap)
00319                         {
00320                                 collided_results.push_back(getNodeData(curIndex));
00321                         }
00322 
00323                         if (aabbOverlap || isleafnode)
00324                         {
00325                                 //next subnode
00326                                 curIndex++;
00327                         }
00328                         else
00329                         {
00330                                 //skip node
00331                                 curIndex+= getScapeNodeIndex(curIndex);
00332                         }
00333                 }
00334                 if(collided_results.size()>0) return true;
00335                 return false;
00336         }
00337 
00339         SIMD_FORCE_INLINE bool boxQueryTrans(const GIM_AABB & box,
00340                  const btTransform & transform, gim_array<GUINT> & collided_results) const
00341         {
00342                 GIM_AABB transbox=box;
00343                 transbox.appy_transform(transform);
00344                 return boxQuery(transbox,collided_results);
00345         }
00346 
00348         SIMD_FORCE_INLINE bool rayQuery(
00349                 const btVector3 & ray_dir,const btVector3 & ray_origin ,
00350                 gim_array<GUINT> & collided_results) const
00351         {
00352                 GUINT curIndex = 0;
00353                 GUINT numNodes = getNodeCount();
00354 
00355                 while (curIndex < numNodes)
00356                 {
00357                         GIM_AABB bound;
00358                         getNodeBound(curIndex,bound);
00359 
00360                         //catch bugs in tree data
00361 
00362                         bool aabbOverlap = bound.collide_ray(ray_origin,ray_dir);
00363                         bool isleafnode = isLeafNode(curIndex);
00364 
00365                         if (isleafnode && aabbOverlap)
00366                         {
00367                                 collided_results.push_back(getNodeData( curIndex));
00368                         }
00369 
00370                         if (aabbOverlap || isleafnode)
00371                         {
00372                                 //next subnode
00373                                 curIndex++;
00374                         }
00375                         else
00376                         {
00377                                 //skip node
00378                                 curIndex+= getScapeNodeIndex(curIndex);
00379                         }
00380                 }
00381                 if(collided_results.size()>0) return true;
00382                 return false;
00383         }
00384 
00386         SIMD_FORCE_INLINE bool hasHierarchy() const
00387         {
00388                 return true;
00389         }
00390 
00392         SIMD_FORCE_INLINE bool isTrimesh()  const
00393         {
00394                 return m_primitive_manager.is_trimesh();
00395         }
00396 
00398         SIMD_FORCE_INLINE GUINT getNodeCount() const
00399         {
00400                 return m_box_tree.getNodeCount();
00401         }
00402 
00404         SIMD_FORCE_INLINE bool isLeafNode(GUINT nodeindex) const
00405         {
00406                 return m_box_tree.isLeafNode(nodeindex);
00407         }
00408 
00409         SIMD_FORCE_INLINE GUINT getNodeData(GUINT nodeindex) const
00410         {
00411                 return m_box_tree.getNodeData(nodeindex);
00412         }
00413 
00414         SIMD_FORCE_INLINE void getNodeBound(GUINT nodeindex, GIM_AABB & bound)  const
00415         {
00416                 m_box_tree.getNodeBound(nodeindex, bound);
00417         }
00418 
00419         SIMD_FORCE_INLINE void setNodeBound(GUINT nodeindex, const GIM_AABB & bound)
00420         {
00421                 m_box_tree.setNodeBound(nodeindex, bound);
00422         }
00423 
00424         SIMD_FORCE_INLINE GUINT getLeftNodeIndex(GUINT nodeindex) const
00425         {
00426                 return m_box_tree.getLeftNodeIndex(nodeindex);
00427         }
00428 
00429         SIMD_FORCE_INLINE GUINT getRightNodeIndex(GUINT nodeindex) const
00430         {
00431                 return m_box_tree.getRightNodeIndex(nodeindex);
00432         }
00433 
00434         SIMD_FORCE_INLINE GUINT getScapeNodeIndex(GUINT nodeindex) const
00435         {
00436                 return m_box_tree.getScapeNodeIndex(nodeindex);
00437         }
00438 
00439         SIMD_FORCE_INLINE void getNodeTriangle(GUINT nodeindex,GIM_TRIANGLE & triangle) const
00440         {
00441                 m_primitive_manager.get_primitive_triangle(getNodeData(nodeindex),triangle);
00442         }
00443 
00444 };
00445 
00447 
00450 template<typename _GIM_PRIMITIVE_MANAGER_PROTOTYPE>
00451 class GIM_BOX_TREE_SET: public GIM_BOX_TREE_TEMPLATE_SET< _GIM_PRIMITIVE_MANAGER_PROTOTYPE, GIM_BOX_TREE>
00452 {
00453 public:
00454 
00455 };
00456 
00457 
00458 
00459 
00460 
00462 template<typename BOX_SET_CLASS0,typename BOX_SET_CLASS1>
00463 class GIM_TREE_TREE_COLLIDER
00464 {
00465 public:
00466         gim_pair_set * m_collision_pairs;
00467         BOX_SET_CLASS0 * m_boxset0;
00468         BOX_SET_CLASS1 * m_boxset1;
00469         GUINT current_node0;
00470         GUINT current_node1;
00471         bool node0_is_leaf;
00472         bool node1_is_leaf;
00473         bool t0_is_trimesh;
00474         bool t1_is_trimesh;
00475         bool node0_has_triangle;
00476         bool node1_has_triangle;
00477         GIM_AABB m_box0;
00478         GIM_AABB m_box1;
00479         GIM_BOX_BOX_TRANSFORM_CACHE trans_cache_1to0;
00480         btTransform trans_cache_0to1;
00481         GIM_TRIANGLE m_tri0;
00482         btVector4 m_tri0_plane;
00483         GIM_TRIANGLE m_tri1;
00484         btVector4 m_tri1_plane;
00485 
00486 
00487 public:
00488         GIM_TREE_TREE_COLLIDER()
00489         {
00490                 current_node0 = G_UINT_INFINITY;
00491                 current_node1 = G_UINT_INFINITY;
00492         }
00493 protected:
00494         SIMD_FORCE_INLINE void retrieve_node0_triangle(GUINT node0)
00495         {
00496                 if(node0_has_triangle) return;
00497                 m_boxset0->getNodeTriangle(node0,m_tri0);
00498                 //transform triangle
00499                 m_tri0.m_vertices[0] = trans_cache_0to1(m_tri0.m_vertices[0]);
00500                 m_tri0.m_vertices[1] = trans_cache_0to1(m_tri0.m_vertices[1]);
00501                 m_tri0.m_vertices[2] = trans_cache_0to1(m_tri0.m_vertices[2]);
00502                 m_tri0.get_plane(m_tri0_plane);
00503 
00504                 node0_has_triangle = true;
00505         }
00506 
00507         SIMD_FORCE_INLINE void retrieve_node1_triangle(GUINT node1)
00508         {
00509                 if(node1_has_triangle) return;
00510                 m_boxset1->getNodeTriangle(node1,m_tri1);
00511                 //transform triangle
00512                 m_tri1.m_vertices[0] = trans_cache_1to0.transform(m_tri1.m_vertices[0]);
00513                 m_tri1.m_vertices[1] = trans_cache_1to0.transform(m_tri1.m_vertices[1]);
00514                 m_tri1.m_vertices[2] = trans_cache_1to0.transform(m_tri1.m_vertices[2]);
00515                 m_tri1.get_plane(m_tri1_plane);
00516 
00517                 node1_has_triangle = true;
00518         }
00519 
00520         SIMD_FORCE_INLINE void retrieve_node0_info(GUINT node0)
00521         {
00522                 if(node0 == current_node0) return;
00523                 m_boxset0->getNodeBound(node0,m_box0);
00524                 node0_is_leaf = m_boxset0->isLeafNode(node0);
00525                 node0_has_triangle = false;
00526                 current_node0 = node0;
00527         }
00528 
00529         SIMD_FORCE_INLINE void retrieve_node1_info(GUINT node1)
00530         {
00531                 if(node1 == current_node1) return;
00532                 m_boxset1->getNodeBound(node1,m_box1);
00533                 node1_is_leaf = m_boxset1->isLeafNode(node1);
00534                 node1_has_triangle = false;
00535                 current_node1 = node1;
00536         }
00537 
00538         SIMD_FORCE_INLINE bool node_collision(GUINT node0 ,GUINT node1)
00539         {
00540                 retrieve_node0_info(node0);
00541                 retrieve_node1_info(node1);
00542                 bool result = m_box0.overlapping_trans_cache(m_box1,trans_cache_1to0,true);
00543                 if(!result) return false;
00544 
00545                 if(t0_is_trimesh && node0_is_leaf)
00546                 {
00547                         //perform primitive vs box collision
00548                         retrieve_node0_triangle(node0);
00549                         //do triangle vs box collision
00550                         m_box1.increment_margin(m_tri0.m_margin);
00551 
00552                         result = m_box1.collide_triangle_exact(
00553                                 m_tri0.m_vertices[0],m_tri0.m_vertices[1],m_tri0.m_vertices[2],m_tri0_plane);
00554 
00555                         m_box1.increment_margin(-m_tri0.m_margin);
00556 
00557                         if(!result) return false;
00558                         return true;
00559                 }
00560                 else if(t1_is_trimesh && node1_is_leaf)
00561                 {
00562                         //perform primitive vs box collision
00563                         retrieve_node1_triangle(node1);
00564                         //do triangle vs box collision
00565                         m_box0.increment_margin(m_tri1.m_margin);
00566 
00567                         result = m_box0.collide_triangle_exact(
00568                                 m_tri1.m_vertices[0],m_tri1.m_vertices[1],m_tri1.m_vertices[2],m_tri1_plane);
00569 
00570                         m_box0.increment_margin(-m_tri1.m_margin);
00571 
00572                         if(!result) return false;
00573                         return true;
00574                 }
00575                 return true;
00576         }
00577 
00578         //stackless collision routine
00579         void find_collision_pairs()
00580         {
00581                 gim_pair_set stack_collisions;
00582                 stack_collisions.reserve(32);
00583 
00584                 //add the first pair
00585                 stack_collisions.push_pair(0,0);
00586 
00587 
00588                 while(stack_collisions.size())
00589                 {
00590                         //retrieve the last pair and pop
00591                         GUINT node0 = stack_collisions.back().m_index1;
00592                         GUINT node1 = stack_collisions.back().m_index2;
00593                         stack_collisions.pop_back();
00594                         if(node_collision(node0,node1)) // a collision is found
00595                         {
00596                                 if(node0_is_leaf)
00597                                 {
00598                                         if(node1_is_leaf)
00599                                         {
00600                                                 m_collision_pairs->push_pair(m_boxset0->getNodeData(node0),m_boxset1->getNodeData(node1));
00601                                         }
00602                                         else
00603                                         {
00604                                                 //collide left
00605                                                 stack_collisions.push_pair(node0,m_boxset1->getLeftNodeIndex(node1));
00606 
00607                                                 //collide right
00608                                                 stack_collisions.push_pair(node0,m_boxset1->getRightNodeIndex(node1));
00609                                         }
00610                                 }
00611                                 else
00612                                 {
00613                                         if(node1_is_leaf)
00614                                         {
00615                                                 //collide left
00616                                                 stack_collisions.push_pair(m_boxset0->getLeftNodeIndex(node0),node1);
00617                                                 //collide right
00618                                                 stack_collisions.push_pair(m_boxset0->getRightNodeIndex(node0),node1);
00619                                         }
00620                                         else
00621                                         {
00622                                                 GUINT left0 = m_boxset0->getLeftNodeIndex(node0);
00623                                                 GUINT right0 = m_boxset0->getRightNodeIndex(node0);
00624                                                 GUINT left1 = m_boxset1->getLeftNodeIndex(node1);
00625                                                 GUINT right1 = m_boxset1->getRightNodeIndex(node1);
00626                                                 //collide left
00627                                                 stack_collisions.push_pair(left0,left1);
00628                                                 //collide right
00629                                                 stack_collisions.push_pair(left0,right1);
00630                                                 //collide left
00631                                                 stack_collisions.push_pair(right0,left1);
00632                                                 //collide right
00633                                                 stack_collisions.push_pair(right0,right1);
00634 
00635                                         }// else if node1 is not a leaf
00636                                 }// else if node0 is not a leaf
00637 
00638                         }// if(node_collision(node0,node1))
00639                 }//while(stack_collisions.size())
00640         }
00641 public:
00642         void find_collision(BOX_SET_CLASS0 * boxset1, const btTransform & trans1,
00643                 BOX_SET_CLASS1 * boxset2, const btTransform & trans2,
00644                 gim_pair_set & collision_pairs, bool complete_primitive_tests = true)
00645         {
00646                 m_collision_pairs = &collision_pairs;
00647                 m_boxset0 = boxset1;
00648                 m_boxset1 = boxset2;
00649 
00650                 trans_cache_1to0.calc_from_homogenic(trans1,trans2);
00651 
00652                 trans_cache_0to1 =  trans2.inverse();
00653                 trans_cache_0to1 *= trans1;
00654 
00655 
00656                 if(complete_primitive_tests)
00657                 {
00658                         t0_is_trimesh = boxset1->getPrimitiveManager().is_trimesh();
00659                         t1_is_trimesh = boxset2->getPrimitiveManager().is_trimesh();
00660                 }
00661                 else
00662                 {
00663                         t0_is_trimesh = false;
00664                         t1_is_trimesh = false;
00665                 }
00666 
00667                 find_collision_pairs();
00668         }
00669 };
00670 
00671 
00672 #endif // GIM_BOXPRUNING_H_INCLUDED
00673 
00674 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31