19 #include "../SpuDoubleBuffer.h"
21 #include "../SpuCollisionTaskProcess.h"
22 #include "../SpuGatheringCollisionDispatcher.h"
25 #include "../SpuContactManifoldCollisionAlgorithm.h"
64 #if USE_SOFTWARE_CACHE
65 #include <spu_intrinsics.h>
66 #include <sys/spu_thread.h>
67 #include <sys/spu_event.h>
69 #define SPE_CACHE_NWAY 4
71 #define SPE_CACHE_NSETS 8
73 #define SPE_CACHELINE_SIZE 128
74 #define SPE_CACHE_SET_TAGID(set) 15
75 #include "../Extras/software_cache/cache/include/spe_cache.h"
82 #if 0 // Added to allow cache misses and hits to be tracked, change this to 1 to restore unmodified version
83 #define spe_cache_read(ea) _spe_cache_lookup_xfer_wait_(ea, 0, 1)
85 #define spe_cache_read(ea) \
87 int set, idx, line, byte; \
88 _spe_cache_nway_lookup_(ea, set, idx); \
90 if (btUnlikely(idx < 0)) { \
92 idx = _spe_cache_miss_(ea, set, -1); \
93 spu_writech(22, SPE_CACHE_SET_TAGMASK(set)); \
94 spu_mfcstat(MFC_TAG_UPDATE_ALL); \
100 line = _spe_cacheline_num_(set, idx); \
101 byte = _spe_cacheline_byte_offset_(ea); \
102 (void *) &spe_cache_mem[line + byte]; \
107 #endif // USE_SOFTWARE_CACHE
112 #include <LibSN_SPU.h>
113 #endif //USE_SN_TUNER
115 #if defined (__SPU__) && !defined (USE_LIBSPE2)
116 #include <spu_printf.h>
117 #elif defined (USE_LIBSPE2)
118 #define spu_printf(a)
120 #define IGNORE_ALIGNMENT 1
123 #define spu_printf printf
160 return m_lsColObj0Ptr;
164 return m_lsColObj1Ptr;
170 return m_pairsPointer;
175 return m_lsCollisionAlgorithmPtr;
180 return m_lsManifoldPtr;
185 #if defined(__CELLOS_LV2__) || defined(USE_LIBSPE2)
191 return &gLocalStoreMemory;
203 sLocalStorePointers.
push_back(localStore);
209 for (
int i=0;i<sLocalStorePointers.
size();i++)
213 sLocalStorePointers.
clear();
223 #if USE_SOFTWARE_CACHE
226 btAssert((ea & ~SPE_CACHELINE_MASK) == ((ea + size - 1) & ~SPE_CACHELINE_MASK));
228 void* ls = spe_cache_read(ea);
229 memcpy(buffer, ls, size);
249 char* localStore0 = (
char*)ls0;
250 uint32_t last4BitsOffset = ea0 & 0x0f;
251 char* tmpTarget0 = tmpBuffer0 + last4BitsOffset;
253 cellDmaSmallGet(tmpTarget0,ea0,size,
DMA_TAG(1),0,0);
259 char* localStore1 = (
char*)ls1;
260 last4BitsOffset = ea1 & 0x0f;
261 char* tmpTarget1 = tmpBuffer1 + last4BitsOffset;
263 cellDmaSmallGet(tmpTarget1,ea1,size,
DMA_TAG(1),0,0);
268 char* localStore2 = (
char*)ls2;
269 last4BitsOffset = ea2 & 0x0f;
270 char* tmpTarget2 = tmpBuffer2 + last4BitsOffset;
272 cellDmaSmallGet(tmpTarget2,ea2,size,
DMA_TAG(1),0,0);
283 localStore0[i] = tmpTarget0[i];
284 localStore1[i] = tmpTarget1[i];
285 localStore2[i] = tmpTarget2[i];
308 : m_wuInput(wuInput),
309 m_spuContacts(spuContacts),
329 sizeof(
unsigned short int));
331 m_lsMemPtr->
spuIndices[0] = int(tmpIndices[0]);
332 m_lsMemPtr->
spuIndices[1] = int(tmpIndices[1]);
333 m_lsMemPtr->
spuIndices[2] = int(tmpIndices[2]);
352 int graphicsindex = m_lsMemPtr->
spuIndices[j];
367 m_tmpTriangleShape.getVertexPtr(j).setValue(spuUnscaledVertex[0]*meshScaling.
getX(),
368 spuUnscaledVertex[1]*meshScaling.
getY(),
369 spuUnscaledVertex[2]*meshScaling.
getZ());
399 bool hasCollision =
false;
400 const btVector3& planeNormal = planeShape->getPlaneNormal();
401 const btScalar& planeConstant = planeShape->getPlaneConstant();
413 btVector3 vtxInPlane = convexInPlaneTrans(vtx);
414 btScalar distance = (planeNormal.
dot(vtxInPlane) - planeConstant);
416 btVector3 vtxInPlaneProjected = vtxInPlane - distance*planeNormal;
433 register int dmaSize = 0;
569 unsigned short int quantizedQueryAabbMin[3];
570 unsigned short int quantizedQueryAabbMax[3];
586 if (subTrees.
size() && indexArray.
size() == 1)
593 int numBatch = subTrees.
size();
594 for (
int i=0;i<numBatch;)
597 int remaining = subTrees.
size() - i;
606 for (
int j=0;j<nextBatch;j++)
641 #define MAX_DEGENERATE_STATS 15
642 int stats[
MAX_DEGENERATE_STATS]={0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
643 int degenerateStats[
MAX_DEGENERATE_STATS]={0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
651 register int dmaSize;
654 #ifdef DEBUG_SPU_COLLISION_DETECTION
656 #endif //DEBUG_SPU_COLLISION_DETECTION
661 bool genericGjk =
true;
679 penetrationSolver = &epaPenetrationSolver2;
777 btGjkPairDetector gjk(shape0Ptr,shape1Ptr,shapeType0,shapeType1,marginA,marginB,&simplexSolver,penetrationSolver);
785 #ifdef USE_SEPDISTANCE_UTIL
789 #endif //USE_SEPDISTANCE_UTIL
799 template<
typename T>
void DoSwap(T& a, T& b)
802 memcpy(tmp, &a,
sizeof(T));
803 memcpy(&a, &b,
sizeof(T));
804 memcpy(&b, tmp,
sizeof(T));
809 register int dmaSize;
834 ppu_address_t collisionShape1Ptr,
void* collisionShape1Loc,
bool dmaShapes =
true)
892 for (
int i = 0; i < childShapeCount0; ++i)
897 for (
int j = 0; j < childShapeCount1; ++j)
937 for (
int i = 0; i < childShapeCount; ++i)
952 collisionShape1Ptr, collisionShape1Loc,
false);
971 for (
int i = 0; i < childShapeCount; ++i)
984 collisionShape0Ptr, collisionShape0Loc,
992 bool handleConvexConcave =
false;
1000 DoSwap(collisionShape0Ptr, collisionShape1Ptr);
1001 DoSwap(collisionShape0Loc, collisionShape1Loc);
1012 handleConvexConcave =
true;
1014 if (handleConvexConcave)
1054 spuContacts.
flush();
1076 unsigned int numPages = taskDesc.
numPages;
1087 register unsigned char *inputPtr;
1088 register unsigned int numOnPage;
1089 register unsigned int j;
1091 register int dmaSize;
1099 for (
unsigned int i = 0;
btLikely(i < numPages); i++)
1106 numOnPage = nextNumOnPage;
1110 #if MIDPHASE_NUM_WORKUNIT_PAGES > 2
1124 for (j = 0;
btLikely( j < numOnPage ); j++)
1126 #ifdef DEBUG_SPU_COLLISION_DETECTION
1128 #endif //DEBUG_SPU_COLLISION_DETECTION
1141 for (p=0;p<numPairs;p++)
1147 #ifdef DEBUG_SPU_COLLISION_DETECTION
1148 spu_printf(
"pair->m_userInfo = %d\n",pair.m_userInfo);
1152 #endif //DEBUG_SPU_COLLISION_DETECTION
1173 #ifdef DEBUG_SPU_COLLISION_DETECTION
1176 #endif //DEBUG_SPU_COLLISION_DETECTION
1205 #ifdef USE_SEPDISTANCE_UTIL
1207 #endif //USE_SEPDISTANCE_UTIL
1209 #define USE_DEDICATED_BOX_BOX 1
1210 #ifdef USE_DEDICATED_BOX_BOX
1232 #ifdef USE_SEPDISTANCE_UTIL
1240 #ifdef USE_PE_BOX_BOX
1263 #ifdef USE_SEPDISTANCE_UTIL
1264 float distanceThreshold = FLT_MAX
1289 boxA, trA, boxB, trB,
1290 distanceThreshold );
1298 if(dist < spuManifold->getContactBreakingThreshold())
1326 m_spuContacts.setShapeIdentifiersA(partId0,index0);
1330 m_spuContacts.setShapeIdentifiersB(partId1,index1);
1334 m_spuContacts.addContactPoint(normalOnBInWorld,pointInWorld,depth);
1338 :m_spuContacts(spuContacts)
1344 SpuBridgeContactCollector bridgeOutput(spuContacts);
1356 #endif //USE_PE_BOX_BOX
1359 #ifdef USE_SEPDISTANCE_UTIL
1362 #endif //USE_SEPDISTANCE_UTIL
1369 spuContacts.
flush();
1373 #endif //USE_DEDICATED_BOX_BOX
1376 #ifdef USE_SEPDISTANCE_UTIL
1380 #endif //USE_SEPDISTANCE_UTIL
1399 spuContacts.
flush();
1408 #ifdef USE_SEPDISTANCE_UTIL
1409 #if defined (__SPU__) || defined (USE_LIBSPE2)
1418 #endif //#ifdef USE_SEPDISTANCE_UTIL
btCollisionObject * getColObj0()
void dmaCompoundShapeInfo(CompoundShape_LocalStoreMemory *compoundShapeLocation, btCompoundShape *spuCompoundShape, uint32_t dmaTag)
char gColObj1Buffer[sizeof(btCollisionObject)+16]
void dmaAndSetupCollisionObjects(SpuCollisionPairInput &collisionPairInput, CollisionTask_LocalStoreMemory &lsMem)
const btVector3 & getLocalScalingNV() const
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
void push_back(const T &_Val)
void computeAabb(btVector3 &aabbMin, btVector3 &aabbMax, btConvexInternalShape *convexShape, ppu_address_t convexShapePtr, int shapeType, const btTransform &xform)
not supported on IBM SDK, until we fix the alignment of btVector3
bvhMeshShape_LocalStoreMemory bvhShapeData
char gSpuContactManifoldAlgoBuffer[sizeof(SpuContactManifoldCollisionAlgorithm)+16]
void quantizeWithClamp(unsigned short *out, const btVector3 &point2, int isMax) const
btBroadphasePair gBroadphasePairsBuffer[128]
This CollisionTask_LocalStoreMemory is mainly used for the SPU version, using explicit DMA Other plat...
SpuContactManifoldCollisionAlgorithm * getlocalCollisionAlgorithm()
btBoxBoxDetector wraps the ODE box-box collision detector re-distributed under the Zlib license with ...
btBvhSubtreeInfo gSubtreeHeaders[32]
int cellDmaGet(void *ls, uint64_t ea, uint32_t size, uint32_t tag, uint32_t tid, uint32_t rid)
The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods It...
float dist(const Point3 &pnt0, const Point3 &pnt1)
btScalar getContactBreakingThreshold() const
void dmaCompoundSubShapes(CompoundShape_LocalStoreMemory *compoundShapeLocation, btCompoundShape *spuCompoundShape, uint32_t dmaTag)
CollisionTask_LocalStoreMemory * m_lsMemPtr
ConvexPenetrationDepthSolver provides an interface for penetration depth calculation.
btScalar getCachedSeparatingDistance() const
DoubleBuffer< unsigned char, MIDPHASE_WORKUNIT_PAGE_SIZE > g_workUnitTaskBuffers
bool gUseEpa
software caching
btBroadphasePair * getBroadphasePairPtr()
ppu_address_t m_inPairPtr
The btConvexInternalShape is an internal base class, shared by most convex shape implementations.
btPersistentManifold gPersistentManifoldBuffer
SpuCollisionPairInput * m_wuInput
Task Description for SPU collision detection.
static DBVT_INLINE btScalar size(const btDbvtVolume &a)
const btVector3 & getScaling() const
#define SIMD_FORCE_INLINE
void dmaBvhSubTreeHeaders(btBvhSubtreeInfo *subTreeHeaders, ppu_address_t subTreePtr, int batchSize, uint32_t dmaTag)
SpuContactResult & m_spuContacts
#define SPU_BATCHSIZE_BROADPHASE_PAIRS
Tuning value to optimized SPU utilization Too small value means Task overhead is large compared to co...
static bool isCompound(int proxyType)
btCollisionShape * m_childShape
void btConvexPlaneCollideSingleContact(SpuCollisionPairInput *wuInput, CollisionTask_LocalStoreMemory *lsMemPtr, SpuContactResult &spuContacts)
int stallingUnalignedDmaSmallGet(void *ls, uint64_t ea, uint32_t size)
this unalignedDma should not be frequently used, only for small data. It handles alignment and perfor...
btQuantizedBvhNode gSubtreeNodes[2048/sizeof(btQuantizedBvhNode)]
void handleCollisionPair(SpuCollisionPairInput &collisionPairInput, CollisionTask_LocalStoreMemory &lsMem, SpuContactResult &spuContacts, ppu_address_t collisionShape0Ptr, void *collisionShape0Loc, ppu_address_t collisionShape1Ptr, void *collisionShape1Loc, bool dmaShapes=true)
int degenerateStats[MAX_DEGENERATE_STATS]
Vectormath::Aos::Vector3 getVmVector3(const btVector3 &bulletVec)
btScalar dot(const btVector3 &v) const
Return the dot product.
int spuIndices[16]
we reserve 32bit integer indices, even though they might be 16bit
char gColObj0Buffer[sizeof(btCollisionObject)+16]
char gSubshapeShape[16][256]
btCollisionObject * m_lsColObj0Ptr
The following pointers might either point into this local store memory, or to the original/other memo...
PHY_ScalarType m_indexType
const btScalar & getZ() const
Return the z value.
The btConvexShape is an abstract shape interface, implemented by all convex shapes such as btBoxShape...
int cellDmaLargePut(const void *ls, uint64_t ea, uint32_t size, uint32_t tag, uint32_t tid, uint32_t rid)
cellDmaLargePut Win32 replacements for Cell DMA to allow simulating most of the SPU code (just memcpy...
void clear()
clear the array, deallocated memory. Generally it is better to use array.resize(0), to reduce performance overhead of run-time memory (de)allocations.
const btVector3 & getCachedSeparatingAxis() const
void dmaBvhIndexedMesh(btIndexedMesh *IndexMesh, IndexedMeshArray &indexArray, int index, uint32_t dmaTag)
btBvhSubtreeInfo provides info to gather a subtree of limited size
btCollisionObject * m_lsColObj1Ptr
void processCollisionTask(void *userPtr, void *lsMemPtr)
The btBvhTriangleMeshShape is a static-triangle mesh shape, it can only be used for fixed/non-moving ...
void deleteCollisionLocalStoreMemory()
btBroadphasePair * m_pairsPointer
void small_cache_read(void *buffer, ppu_address_t ea, size_t size)
btTransform & getWorldTransform()
virtual void setShapeIdentifiersB(int partId1, int index1)=0
int size() const
return the number of elements in the array
void setPoints(btVector3 *points, int numPoints, bool computeAabb=true, const btVector3 &localScaling=btVector3(1.f, 1.f, 1.f))
#define MAX_DEGENERATE_STATS
btVoronoiSimplexSolver is an implementation of the closest point distance algorithm from a 1-4 points...
int m_triangleIndexStride
btIndexedMesh gIndexMesh
only a single mesh part for now, we can add support for multiple parts, but quantized trees don't sup...
IndexedMeshArray & getIndexedMeshArray()
const btScalar & getY() const
Return the y value.
#define btAlignedFree(ptr)
btCollisionObject can be used to manage collision detection objects.
const btScalar & getX() const
Return the x value.
void ProcessConvexConcaveSpuCollision(SpuCollisionPairInput *wuInput, CollisionTask_LocalStoreMemory *lsMemPtr, SpuContactResult &spuContacts)
Convex versus Concave triangle mesh collision detection (handles concave triangle mesh versus sphere...
void * cellDmaGetReadOnly(void *ls, uint64_t ea, uint32_t size, uint32_t tag, uint32_t tid, uint32_t rid)
virtual void getClosestPoints(const ClosestPointInput &input, Result &output, class btIDebugDraw *debugDraw, bool swapResults=false)
void cellDmaWaitTagStatusAll(int ignore)
cellDmaWaitTagStatusAll Win32 replacements for Cell DMA to allow simulating most of the SPU code (jus...
btScalar getRestitution() const
const unsigned char * m_triangleIndexBase
btVector3 localGetSupportVertexNonVirtual(const btVector3 &vec) const
btPersistentManifold * getContactManifoldPtr()
btBroadphaseProxy * m_pProxy1
btCollisionAlgorithm * m_algorithm
void * cellDmaSmallGetReadOnly(void *ls, uint64_t ea, uint32_t size, uint32_t tag, uint32_t tid, uint32_t rid)
The btBoxShape is a box primitive around the origin, its sides axis aligned with length specified by ...
btVector3 can be used to represent 3D points and vectors.
#define ATTRIBUTE_ALIGNED16(a)
btBroadphaseProxy * m_pProxy0
void dmaCollisionShape(void *collisionShapeLocation, ppu_address_t collisionShapePtr, uint32_t dmaTag, int shapeType)
void dmaBvhShapeData(bvhMeshShape_LocalStoreMemory *bvhMeshShape, btBvhTriangleMeshShape *triMeshShape)
unsigned short int m_quantizedAabbMax[3]
Vectormath::Aos::Matrix3 getVmMatrix3(const btMatrix3x3 &btMat)
CollisionShape_LocalStoreMemory gCollisionShapes[2]
EpaPenetrationDepthSolver uses the Expanding Polytope Algorithm to calculate the penetration depth be...
virtual void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar depth)=0
btVector3 getBtVector3(const Vectormath::Aos::Vector3 &vmVec)
#define MIDPHASE_NUM_WORKUNITS_PER_PAGE
The Box is an internal class used by the boxBoxDistance calculation.
const btVector3 & getImplicitShapeDimensions() const
btVector3 * gConvexPoints
BvhSubtreeInfoArray & getSubtreeInfoArray()
void ProcessConvexPlaneSpuCollision(SpuCollisionPairInput *wuInput, CollisionTask_LocalStoreMemory *lsMemPtr, SpuContactResult &spuContacts)
Make sure no destructors are called on this memory.
SpuConvexPolyhedronVertexData convexVertexData[2]
CompoundShape_LocalStoreMemory compoundShapeData[2]
void small_cache_read_triple(void *ls0, ppu_address_t ea0, void *ls1, ppu_address_t ea1, void *ls2, ppu_address_t ea2, size_t size)
bool needsDmaPutContactManifoldAlgo
btScalar getFriction() const
btGjkPairDetector uses GJK to implement the btDiscreteCollisionDetectorInterface
float boxBoxDistance(vmVector3 &normal, BoxPoint &boxPointA, BoxPoint &boxPointB, PE_REF(Box) boxA, const vmTransform3 &transformA, PE_REF(Box) boxB, const vmTransform3 &transformB, float distanceThreshold)
btPersistentManifold * m_lsManifoldPtr
static bool isConcave(int proxyType)
void spuWalkStacklessQuantizedTree(btNodeOverlapCallback *nodeCallback, unsigned short int *quantizedQueryAabbMin, unsigned short int *quantizedQueryAabbMax, const btQuantizedBvhNode *rootNode, int startNodeIndex, int endNodeIndex)
void backBufferDmaGet(uint64_t ea, unsigned int numBytes, unsigned int tag)
void * createCollisionLocalStoreMemory()
#define btAlignedAlloc(size, alignment)
The btConvexHullShape implements an implicit convex hull of an array of vertices. ...
btTriangleIndexVertexArray * gTriangleMeshInterfacePtr
The btConvexPointCloudShape implements an implicit convex hull of an array of vertices.
The btCompoundShape allows to store multiple other btCollisionShapes This allows for moving concave c...
The BoxPoint class is an internally used class to contain feature information for boxBoxDistance calc...
SpuContactManifoldCollisionAlgorithm * m_lsCollisionAlgorithmPtr
void dmaConvexVertexData(SpuConvexPolyhedronVertexData *convexVertexData, btConvexHullShape *convexShapeSPU)
The btStaticPlaneShape simulates an infinite non-moving (static) collision plane. ...
btCompoundShapeChild gSubshapes[16]
#define MAX_SPU_COMPOUND_SUBSHAPES
unsigned short int m_quantizedAabbMin[3]
virtual void setShapeIdentifiersA(int partId0, int index0)=0
setShapeIdentifiersA/B provides experimental support for per-triangle material / custom material comb...
void ProcessSpuConvexConvexCollision(SpuCollisionPairInput *wuInput, CollisionTask_LocalStoreMemory *lsMemPtr, SpuContactResult &spuContacts)
Convex versus Convex collision detection (handles collision between sphere, box, cylinder, triangle, cone, convex polyhedron etc)
const btCollisionShape * getCollisionShape() const
unsigned int spuTestQuantizedAabbAgainstQuantizedAabb(unsigned short int *aabbMin1, unsigned short int *aabbMax1, const unsigned short int *aabbMin2, const unsigned short int *aabbMax2)
QuantizedNodeArray & getQuantizedNodeArray()
int stats[MAX_DEGENERATE_STATS]
void dmaBvhSubTreeNodes(btQuantizedBvhNode *nodes, const btBvhSubtreeInfo &subtree, QuantizedNodeArray &nodeArray, int dmaTag)
#define MIDPHASE_WORKUNIT_PAGE_SIZE
virtual void processNode(int subPart, int triangleIndex)
#define MAX_SPU_SUBTREE_HEADERS
btOptimizedBvh * getOptimizedBvh()
static bool isConvex(int proxyType)
btVector3 g_convexPointBuffer[128]
btAlignedObjectArray< CollisionTask_LocalStoreMemory * > sLocalStorePointers
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
btCollisionObject * getColObj1()
void * gSpuConvexShapePtr
virtual void getClosestPoints(const ClosestPointInput &input, Result &output, class btIDebugDraw *debugDraw, bool swapResults=false)
const unsigned char * m_vertexBase
int getNumChildShapes() const
The btBroadphasePair class contains a pair of aabb-overlapping objects.