OPC_OptimizedTree.cpp
Go to the documentation of this file.
1 /*
3  * OPCODE - Optimized Collision Detection
4  * Copyright (C) 2001 Pierre Terdiman
5  * Homepage: http://www.codercorner.com/Opcode.htm
6  */
8 
10 
21 
24 
32 
35 
43 
46 
54 
57 
65 
68 // Precompiled Header
69 #include "Stdafx.h"
70 
71 using namespace Opcode;
72 
76 static bool gFixQuantized = true;
77 
79 
98 static void _BuildCollisionTree(AABBCollisionNode* linear, const udword box_id, udword& current_id, const AABBTreeNode* current_node)
100 {
101  // Current node from input tree is "current_node". Must be flattened into "linear[boxid]".
102 
103  // Store the AABB
104  current_node->GetAABB()->GetCenter(linear[box_id].mAABB.mCenter);
105  current_node->GetAABB()->GetExtents(linear[box_id].mAABB.mExtents);
106 #if 1 // Added by AIST
107  linear[box_id].mAABB.CreateSSV();
108 #endif
109  // Store remaining info
110  if(current_node->IsLeaf())
111  {
112  // The input tree must be complete => i.e. one primitive/leaf
113  ASSERT(current_node->GetNbPrimitives()==1);
114  // Get the primitive index from the input tree
115  udword PrimitiveIndex = current_node->GetPrimitives()[0];
116  // Setup box data as the primitive index, marked as leaf
117  linear[box_id].mData = (PrimitiveIndex<<1)|1;
118  }
119  else
120  {
121  // To make the negative one implicit, we must store P and N in successive order
122  udword PosID = current_id++; // Get a new id for positive child
123  udword NegID = current_id++; // Get a new id for negative child
124  // Setup box data as the forthcoming new P pointer
125  linear[box_id].mData = (EXWORD)&linear[PosID];
126  // Make sure it's not marked as leaf
127  ASSERT(!(linear[box_id].mData&1));
128 
129  //Modified by S-cubed, Inc.
130  //examine_normal_vector@InsertCollisionPair.cpp $B$G?F$rDI$($k$h$&$K$9$k(B
131  ((AABBCollisionNode*)linear[box_id].mData)->mB = &linear[box_id];
132  (((AABBCollisionNode*)linear[box_id].mData)+1)->mB = &linear[box_id];
133  // Recurse with new IDs
134  _BuildCollisionTree(linear, PosID, current_id, current_node->GetPos());
135  _BuildCollisionTree(linear, NegID, current_id, current_node->GetNeg());
136  }
137 }
138 
140 
157 static void _BuildNoLeafTree(AABBNoLeafNode* linear, const udword box_id, udword& current_id, const AABBTreeNode* current_node)
159 {
160  const AABBTreeNode* P = current_node->GetPos();
161  const AABBTreeNode* N = current_node->GetNeg();
162  // Leaf nodes here?!
163  ASSERT(P);
164  ASSERT(N);
165  // Internal node => keep the box
166  current_node->GetAABB()->GetCenter(linear[box_id].mAABB.mCenter);
167  current_node->GetAABB()->GetExtents(linear[box_id].mAABB.mExtents);
168 
169  if(P->IsLeaf())
170  {
171  // The input tree must be complete => i.e. one primitive/leaf
172  ASSERT(P->GetNbPrimitives()==1);
173  // Get the primitive index from the input tree
174  udword PrimitiveIndex = P->GetPrimitives()[0];
175  // Setup prev box data as the primitive index, marked as leaf
176  linear[box_id].mPosData = (PrimitiveIndex<<1)|1;
177  }
178  else
179  {
180  // Get a new id for positive child
181  udword PosID = current_id++;
182  // Setup box data
183  linear[box_id].mPosData = (EXWORD)&linear[PosID];
184  // Make sure it's not marked as leaf
185  ASSERT(!(linear[box_id].mPosData&1));
186  // Recurse
187  _BuildNoLeafTree(linear, PosID, current_id, P);
188  }
189 
190  if(N->IsLeaf())
191  {
192  // The input tree must be complete => i.e. one primitive/leaf
193  ASSERT(N->GetNbPrimitives()==1);
194  // Get the primitive index from the input tree
195  udword PrimitiveIndex = N->GetPrimitives()[0];
196  // Setup prev box data as the primitive index, marked as leaf
197  linear[box_id].mNegData = (PrimitiveIndex<<1)|1;
198  }
199  else
200  {
201  // Get a new id for negative child
202  udword NegID = current_id++;
203  // Setup box data
204  linear[box_id].mNegData = (EXWORD)&linear[NegID];
205  // Make sure it's not marked as leaf
206  ASSERT(!(linear[box_id].mNegData&1));
207  // Recurse
208  _BuildNoLeafTree(linear, NegID, current_id, N);
209  }
210 }
211 
213 
216 AABBCollisionTree::AABBCollisionTree() : mNodes(null)
218 {
219 }
220 
222 
225 AABBCollisionTree::~AABBCollisionTree()
227 {
228  DELETEARRAY(mNodes);
229 }
230 
232 
239 {
240  // Checkings
241  if(!tree) return false;
242  // Check the input tree is complete
243  udword NbTriangles = tree->GetNbPrimitives();
244  udword NbNodes = tree->GetNbNodes();
245  if(NbNodes!=NbTriangles*2-1) return false;
246 
247  // Get nodes
248  if(mNbNodes!=NbNodes) // Same number of nodes => keep moving
249  {
250  mNbNodes = NbNodes;
251  DELETEARRAY(mNodes);
252  mNodes = new AABBCollisionNode[mNbNodes];
253  CHECKALLOC(mNodes);
254  }
255 
256  // Build the tree
257  udword CurID = 1;
258 
259  // Modified by S-cubed, Inc.
260  //$B%k!<%H$N?F$O<+J,<+?H(B
261  mNodes[0].mB = &mNodes[0];
262 
263  _BuildCollisionTree(mNodes, 0, CurID, tree);
264  ASSERT(CurID==mNbNodes);
265 
266  return true;
267 }
268 
270 
275 bool AABBCollisionTree::Refit(const MeshInterface* mesh_interface)
277 {
278  ASSERT(!"Not implemented since AABBCollisionTrees have twice as more nodes to refit as AABBNoLeafTrees!");
279  return false;
280 }
281 
283 
289 bool AABBCollisionTree::Walk(GenericWalkingCallback callback, void* user_data) const
291 {
292  if(!callback) return false;
293 
294  struct Local
295  {
296  static void _Walk(const AABBCollisionNode* current_node, GenericWalkingCallback callback, void* user_data)
297  {
298  if(!current_node || !(callback)(current_node, user_data)) return;
299 
300  if(!current_node->IsLeaf())
301  {
302  _Walk(current_node->GetPos(), callback, user_data);
303  _Walk(current_node->GetNeg(), callback, user_data);
304  }
305  }
306  };
307  Local::_Walk(mNodes, callback, user_data);
308  return true;
309 }
310 
311 
313 
316 AABBNoLeafTree::AABBNoLeafTree() : mNodes(null)
318 {
319 }
320 
322 
325 AABBNoLeafTree::~AABBNoLeafTree()
327 {
328  DELETEARRAY(mNodes);
329 }
330 
332 
339 {
340  // Checkings
341  if(!tree) return false;
342  // Check the input tree is complete
343  udword NbTriangles = tree->GetNbPrimitives();
344  udword NbNodes = tree->GetNbNodes();
345  if(NbNodes!=NbTriangles*2-1) return false;
346 
347  // Get nodes
348  if(mNbNodes!=NbTriangles-1) // Same number of nodes => keep moving
349  {
350  mNbNodes = NbTriangles-1;
351  DELETEARRAY(mNodes);
352  mNodes = new AABBNoLeafNode[mNbNodes];
353  CHECKALLOC(mNodes);
354  }
355 
356  // Build the tree
357  udword CurID = 1;
358  _BuildNoLeafTree(mNodes, 0, CurID, tree);
359  ASSERT(CurID==mNbNodes);
360 
361  return true;
362 }
363 
365 {
366  // Compute triangle's AABB = a leaf box
367 #ifdef OPC_USE_FCOMI // a 15% speedup on my machine, not much
368  min.x = FCMin3(vp.Vertex[0]->x, vp.Vertex[1]->x, vp.Vertex[2]->x);
369  max.x = FCMax3(vp.Vertex[0]->x, vp.Vertex[1]->x, vp.Vertex[2]->x);
370 
371  min.y = FCMin3(vp.Vertex[0]->y, vp.Vertex[1]->y, vp.Vertex[2]->y);
372  max.y = FCMax3(vp.Vertex[0]->y, vp.Vertex[1]->y, vp.Vertex[2]->y);
373 
374  min.z = FCMin3(vp.Vertex[0]->z, vp.Vertex[1]->z, vp.Vertex[2]->z);
375  max.z = FCMax3(vp.Vertex[0]->z, vp.Vertex[1]->z, vp.Vertex[2]->z);
376 #else
377  min = *vp.Vertex[0];
378  max = *vp.Vertex[0];
379  min.Min(*vp.Vertex[1]);
380  max.Max(*vp.Vertex[1]);
381  min.Min(*vp.Vertex[2]);
382  max.Max(*vp.Vertex[2]);
383 #endif
384 }
385 
387 
392 bool AABBNoLeafTree::Refit(const MeshInterface* mesh_interface)
394 {
395  // Checkings
396  if(!mesh_interface) return false;
397 
398  // Bottom-up update
399  VertexPointers VP;
400  Point Min,Max;
401  Point Min_,Max_;
402  udword Index = mNbNodes;
403  while(Index--)
404  {
405  AABBNoLeafNode& Current = mNodes[Index];
406 
407  if(Current.HasPosLeaf())
408  {
409  mesh_interface->GetTriangle(VP, Current.GetPosPrimitive());
410  ComputeMinMax(Min, Max, VP);
411  }
412  else
413  {
414  const CollisionAABB& CurrentBox = Current.GetPos()->mAABB;
415  CurrentBox.GetMin(Min);
416  CurrentBox.GetMax(Max);
417  }
418 
419  if(Current.HasNegLeaf())
420  {
421  mesh_interface->GetTriangle(VP, Current.GetNegPrimitive());
422  ComputeMinMax(Min_, Max_, VP);
423  }
424  else
425  {
426  const CollisionAABB& CurrentBox = Current.GetNeg()->mAABB;
427  CurrentBox.GetMin(Min_);
428  CurrentBox.GetMax(Max_);
429  }
430 #ifdef OPC_USE_FCOMI
431  Min.x = FCMin2(Min.x, Min_.x);
432  Max.x = FCMax2(Max.x, Max_.x);
433  Min.y = FCMin2(Min.y, Min_.y);
434  Max.y = FCMax2(Max.y, Max_.y);
435  Min.z = FCMin2(Min.z, Min_.z);
436  Max.z = FCMax2(Max.z, Max_.z);
437 #else
438  Min.Min(Min_);
439  Max.Max(Max_);
440 #endif
441  Current.mAABB.SetMinMax(Min, Max);
442  }
443  return true;
444 }
445 
447 
453 bool AABBNoLeafTree::Walk(GenericWalkingCallback callback, void* user_data) const
455 {
456  if(!callback) return false;
457 
458  struct Local
459  {
460  static void _Walk(const AABBNoLeafNode* current_node, GenericWalkingCallback callback, void* user_data)
461  {
462  if(!current_node || !(callback)(current_node, user_data)) return;
463 
464  if(!current_node->HasPosLeaf()) _Walk(current_node->GetPos(), callback, user_data);
465  if(!current_node->HasNegLeaf()) _Walk(current_node->GetNeg(), callback, user_data);
466  }
467  };
468  Local::_Walk(mNodes, callback, user_data);
469  return true;
470 }
471 
472 // Quantization notes:
473 // - We could use the highest bits of mData to store some more quantized bits. Dequantization code
474 // would be slightly more complex, but number of overlap tests would be reduced (and anyhow those
475 // bits are currently wasted). Of course it's not possible if we move to 16 bits mData.
476 // - Something like "16 bits floats" could be tested, to bypass the int-to-float conversion.
477 // - A dedicated BV-BV test could be used, dequantizing while testing for overlap. (i.e. it's some
478 // lazy-dequantization which may save some work in case of early exits). At the very least some
479 // muls could be saved by precomputing several more matrices. But maybe not worth the pain.
480 // - Do we need to dequantize anyway? Not doing the extents-related muls only implies the box has
481 // been scaled, for example.
482 // - The deeper we move into the hierarchy, the smaller the extents should be. May not need a fixed
483 // number of quantization bits. Even better, could probably be best delta-encoded.
484 
485 
486 // Find max values. Some people asked why I wasn't simply using the first node. Well, I can't.
487 // I'm not looking for (min, max) values like in a standard AABB, I'm looking for the extremal
488 // centers/extents in order to quantize them. The first node would only give a single center and
489 // a single extents. While extents would be the biggest, the center wouldn't.
490 #define FIND_MAX_VALUES \
491  /* Get max values */ \
492  Point CMax(MIN_FLOAT, MIN_FLOAT, MIN_FLOAT); \
493  Point EMax(MIN_FLOAT, MIN_FLOAT, MIN_FLOAT); \
494  for(udword i=0;i<mNbNodes;i++) \
495  { \
496  if(fabsf(Nodes[i].mAABB.mCenter.x)>CMax.x) CMax.x = fabsf(Nodes[i].mAABB.mCenter.x); \
497  if(fabsf(Nodes[i].mAABB.mCenter.y)>CMax.y) CMax.y = fabsf(Nodes[i].mAABB.mCenter.y); \
498  if(fabsf(Nodes[i].mAABB.mCenter.z)>CMax.z) CMax.z = fabsf(Nodes[i].mAABB.mCenter.z); \
499  if(fabsf(Nodes[i].mAABB.mExtents.x)>EMax.x) EMax.x = fabsf(Nodes[i].mAABB.mExtents.x); \
500  if(fabsf(Nodes[i].mAABB.mExtents.y)>EMax.y) EMax.y = fabsf(Nodes[i].mAABB.mExtents.y); \
501  if(fabsf(Nodes[i].mAABB.mExtents.z)>EMax.z) EMax.z = fabsf(Nodes[i].mAABB.mExtents.z); \
502  }
503 
504 #define INIT_QUANTIZATION \
505  udword nbc=15; /* Keep one bit for sign */ \
506  udword nbe=15; /* Keep one bit for fix */ \
507  if(!gFixQuantized) nbe++; \
508  \
509  /* Compute quantization coeffs */ \
510  Point CQuantCoeff, EQuantCoeff; \
511  CQuantCoeff.x = CMax.x!=0.0f ? float((1<<nbc)-1)/CMax.x : 0.0f; \
512  CQuantCoeff.y = CMax.y!=0.0f ? float((1<<nbc)-1)/CMax.y : 0.0f; \
513  CQuantCoeff.z = CMax.z!=0.0f ? float((1<<nbc)-1)/CMax.z : 0.0f; \
514  EQuantCoeff.x = EMax.x!=0.0f ? float((1<<nbe)-1)/EMax.x : 0.0f; \
515  EQuantCoeff.y = EMax.y!=0.0f ? float((1<<nbe)-1)/EMax.y : 0.0f; \
516  EQuantCoeff.z = EMax.z!=0.0f ? float((1<<nbe)-1)/EMax.z : 0.0f; \
517  /* Compute and save dequantization coeffs */ \
518  mCenterCoeff.x = CQuantCoeff.x!=0.0f ? 1.0f / CQuantCoeff.x : 0.0f; \
519  mCenterCoeff.y = CQuantCoeff.y!=0.0f ? 1.0f / CQuantCoeff.y : 0.0f; \
520  mCenterCoeff.z = CQuantCoeff.z!=0.0f ? 1.0f / CQuantCoeff.z : 0.0f; \
521  mExtentsCoeff.x = EQuantCoeff.x!=0.0f ? 1.0f / EQuantCoeff.x : 0.0f; \
522  mExtentsCoeff.y = EQuantCoeff.y!=0.0f ? 1.0f / EQuantCoeff.y : 0.0f; \
523  mExtentsCoeff.z = EQuantCoeff.z!=0.0f ? 1.0f / EQuantCoeff.z : 0.0f; \
524 
525 #define PERFORM_QUANTIZATION \
526  /* Quantize */ \
527  mNodes[i].mAABB.mCenter[0] = sword(Nodes[i].mAABB.mCenter.x * CQuantCoeff.x); \
528  mNodes[i].mAABB.mCenter[1] = sword(Nodes[i].mAABB.mCenter.y * CQuantCoeff.y); \
529  mNodes[i].mAABB.mCenter[2] = sword(Nodes[i].mAABB.mCenter.z * CQuantCoeff.z); \
530  mNodes[i].mAABB.mExtents[0] = uword(Nodes[i].mAABB.mExtents.x * EQuantCoeff.x); \
531  mNodes[i].mAABB.mExtents[1] = uword(Nodes[i].mAABB.mExtents.y * EQuantCoeff.y); \
532  mNodes[i].mAABB.mExtents[2] = uword(Nodes[i].mAABB.mExtents.z * EQuantCoeff.z); \
533  /* Fix quantized boxes */ \
534  if(gFixQuantized) \
535  { \
536  /* Make sure the quantized box is still valid */ \
537  Point Max = Nodes[i].mAABB.mCenter + Nodes[i].mAABB.mExtents; \
538  Point Min = Nodes[i].mAABB.mCenter - Nodes[i].mAABB.mExtents; \
539  /* For each axis */ \
540  for(udword j=0;j<3;j++) \
541  { /* Dequantize the box center */ \
542  float qc = float(mNodes[i].mAABB.mCenter[j]) * mCenterCoeff[j]; \
543  bool FixMe=true; \
544  do \
545  { /* Dequantize the box extent */ \
546  float qe = float(mNodes[i].mAABB.mExtents[j]) * mExtentsCoeff[j]; \
547  /* Compare real & dequantized values */ \
548  if(qc+qe<Max[j] || qc-qe>Min[j]) mNodes[i].mAABB.mExtents[j]++; \
549  else FixMe=false; \
550  /* Prevent wrapping */ \
551  if(!mNodes[i].mAABB.mExtents[j]) \
552  { \
553  mNodes[i].mAABB.mExtents[j]=0xffff; \
554  FixMe=false; \
555  } \
556  }while(FixMe); \
557  } \
558  }
559 
560 #if (defined __x86_64) || (defined __aarch64__)
561 #define REMAP_DATA(member) \
562  /* Fix data */ \
563  Data = Nodes[i].member; \
564  if(!(Data&1)) \
565  { \
566  /* Compute box number */ \
567  uqword Nb = (Data - uqword(Nodes))/Nodes[i].GetNodeSize(); \
568  Data = uqword(&mNodes[Nb]); \
569  } \
570  /* ...remapped */ \
571  mNodes[i].member = Data;
572 #else
573 #define REMAP_DATA(member) \
574  /* Fix data */ \
575  Data = Nodes[i].member; \
576  if(!(Data&1)) \
577  { \
578  /* Compute box number */ \
579  udword Nb = (Data - udword(Nodes))/Nodes[i].GetNodeSize(); \
580  Data = udword(&mNodes[Nb]); \
581  } \
582  /* ...remapped */ \
583  mNodes[i].member = Data;
584 #endif
585 
587 
590 AABBQuantizedTree::AABBQuantizedTree() : mNodes(null)
592 {
593 }
594 
596 
599 AABBQuantizedTree::~AABBQuantizedTree()
601 {
602  DELETEARRAY(mNodes);
603 }
604 
606 
613 {
614  // Checkings
615  if(!tree) return false;
616  // Check the input tree is complete
617  udword NbTriangles = tree->GetNbPrimitives();
618  udword NbNodes = tree->GetNbNodes();
619  if(NbNodes!=NbTriangles*2-1) return false;
620 
621  // Get nodes
622  mNbNodes = NbNodes;
623  DELETEARRAY(mNodes);
625  CHECKALLOC(Nodes);
626 
627  // Build the tree
628  udword CurID = 1;
629  _BuildCollisionTree(Nodes, 0, CurID, tree);
630 
631  // Quantize
632  {
633  mNodes = new AABBQuantizedNode[mNbNodes];
634  CHECKALLOC(mNodes);
635 
636  // Get max values
638 
639  // Quantization
641 
642  // Quantize
643  EXWORD Data;
644  for(udword i=0;i<mNbNodes;i++)
645  {
647  REMAP_DATA(mData)
648  }
649 
650  DELETEARRAY(Nodes);
651  }
652 
653  return true;
654 }
655 
657 
662 bool AABBQuantizedTree::Refit(const MeshInterface* mesh_interface)
664 {
665  ASSERT(!"Not implemented since requantizing is painful !");
666  return false;
667 }
668 
670 
676 bool AABBQuantizedTree::Walk(GenericWalkingCallback callback, void* user_data) const
678 {
679  if(!callback) return false;
680 
681  struct Local
682  {
683  static void _Walk(const AABBQuantizedNode* current_node, GenericWalkingCallback callback, void* user_data)
684  {
685  if(!current_node || !(callback)(current_node, user_data)) return;
686 
687  if(!current_node->IsLeaf())
688  {
689  _Walk(current_node->GetPos(), callback, user_data);
690  _Walk(current_node->GetNeg(), callback, user_data);
691  }
692  }
693  };
694  Local::_Walk(mNodes, callback, user_data);
695  return true;
696 }
697 
698 
699 
701 
704 AABBQuantizedNoLeafTree::AABBQuantizedNoLeafTree() : mNodes(null)
706 {
707 }
708 
710 
713 AABBQuantizedNoLeafTree::~AABBQuantizedNoLeafTree()
715 {
716  DELETEARRAY(mNodes);
717 }
718 
720 
727 {
728  // Checkings
729  if(!tree) return false;
730  // Check the input tree is complete
731  udword NbTriangles = tree->GetNbPrimitives();
732  udword NbNodes = tree->GetNbNodes();
733  if(NbNodes!=NbTriangles*2-1) return false;
734 
735  // Get nodes
736  mNbNodes = NbTriangles-1;
737  DELETEARRAY(mNodes);
738  AABBNoLeafNode* Nodes = new AABBNoLeafNode[mNbNodes];
739  CHECKALLOC(Nodes);
740 
741  // Build the tree
742  udword CurID = 1;
743  _BuildNoLeafTree(Nodes, 0, CurID, tree);
744  ASSERT(CurID==mNbNodes);
745 
746  // Quantize
747  {
748  mNodes = new AABBQuantizedNoLeafNode[mNbNodes];
749  CHECKALLOC(mNodes);
750 
751  // Get max values
753 
754  // Quantization
756 
757  // Quantize
758  EXWORD Data;
759  for(udword i=0;i<mNbNodes;i++)
760  {
762  REMAP_DATA(mPosData)
763  REMAP_DATA(mNegData)
764  }
765 
766  DELETEARRAY(Nodes);
767  }
768 
769  return true;
770 }
771 
773 
778 bool AABBQuantizedNoLeafTree::Refit(const MeshInterface* mesh_interface)
780 {
781  ASSERT(!"Not implemented since requantizing is painful !");
782  return false;
783 }
784 
786 
792 bool AABBQuantizedNoLeafTree::Walk(GenericWalkingCallback callback, void* user_data) const
794 {
795  if(!callback) return false;
796 
797  struct Local
798  {
799  static void _Walk(const AABBQuantizedNoLeafNode* current_node, GenericWalkingCallback callback, void* user_data)
800  {
801  if(!current_node || !(callback)(current_node, user_data)) return;
802 
803  if(!current_node->HasPosLeaf()) _Walk(current_node->GetPos(), callback, user_data);
804  if(!current_node->HasNegLeaf()) _Walk(current_node->GetNeg(), callback, user_data);
805  }
806  };
807  Local::_Walk(mNodes, callback, user_data);
808  return true;
809 }
inline_ float FCMin2(float a, float b)
A global function to find MIN(a,b) using FCOMI/FCMOV.
Definition: IceFPU.h:244
inline_ void GetTriangle(VertexPointers &vp, udword index) const
Definition: Opcode.h:119
inline_ const udword * GetPrimitives() const
Definition: Opcode.h:89
inline_ void GetMin(Point &min) const
Get min point of the box.
Definition: Opcode.h:42
inline_ void ComputeMinMax(Point &min, Point &max, const VertexPointers &vp)
#define null
our own NULL pointer
Definition: IceTypes.h:57
static int min(int a, int b)
#define DELETEARRAY(x)
Deletes an array.
#define inline_
const Point * Vertex[3]
Definition: Opcode.h:26
inline_ void GetMax(Point &max) const
Get max point of the box.
Definition: Opcode.h:44
png_uint_32 i
Definition: png.h:2735
bool(* GenericWalkingCallback)(const void *current, void *user_data)
Definition: Opcode.h:146
#define INIT_QUANTIZATION
unsigned int udword
sizeof(udword) must be 4
Definition: IceTypes.h:65
#define REMAP_DATA(member)
inline_ float Min() const
Returns MIN(x, y, z);.
Definition: OPC_IceHook.h:200
#define CHECKALLOC(x)
#define PERFORM_QUANTIZATION
inline_ float Max() const
Returns MAX(x, y, z);.
Definition: OPC_IceHook.h:202
virtual bool Build(AABBTree *tree)=0
static void _BuildCollisionTree(AABBCollisionNode *linear, const udword box_id, udword &current_id, const AABBTreeNode *current_node)
static bool gFixQuantized
virtual bool Walk(GenericWalkingCallback callback, void *user_data) const =0
#define FIND_MAX_VALUES
#define ASSERT(exp)
Definition: OPC_IceHook.h:24
virtual bool Refit(const MeshInterface *mesh_interface)=0
static void _BuildNoLeafTree(AABBNoLeafNode *linear, const udword box_id, udword &current_id, const AABBTreeNode *current_node)
#define EXWORD
Definition: Opcode.h:27
inline_ float FCMin3(float a, float b, float c)
A global function to find MIN(a,b,c) using FCOMI/FCMOV.
Definition: IceFPU.h:281
inline_ float FCMax3(float a, float b, float c)
A global function to find MAX(a,b,c) using FCOMI/FCMOV.
Definition: IceFPU.h:261
inline_ udword GetNbPrimitives() const
Definition: Opcode.h:90
inline_ udword GetNbNodes() const
Catch the number of nodes.
Definition: Opcode.h:126
inline_ float FCMax2(float a, float b)
A global function to find MAX(a,b) using FCOMI/FCMOV.
Definition: IceFPU.h:227
static int max(int a, int b)


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat Apr 13 2019 02:14:24