some doxygen updates, added some comments to classes, fix broken links, rename some prefix some internal GIMPACT collision structures using (for example use GIM_AABB instead of BT_AAABB),

removed obsolete btGjkEpa (it was replaced by btGjkEpa2 ages ago)
This commit is contained in:
erwin.coumans 2008-11-04 04:01:31 +00:00
parent 2b21eb5605
commit bcd0f48c28
83 changed files with 208 additions and 1089 deletions

View File

@ -38,37 +38,37 @@ typedef plReal plQuaternion[4];
extern "C" {
#endif
/* Particular physics SDK */
/** Particular physics SDK (C-API) */
PL_DECLARE_HANDLE(plPhysicsSdkHandle);
/* Dynamics world, belonging to some physics SDK */
/** Dynamics world, belonging to some physics SDK (C-API)*/
PL_DECLARE_HANDLE(plDynamicsWorldHandle);
/* Rigid Body that can be part of a Dynamics World */
/** Rigid Body that can be part of a Dynamics World (C-API)*/
PL_DECLARE_HANDLE(plRigidBodyHandle);
/* Collision Shape/Geometry, property of a Rigid Body */
/** Collision Shape/Geometry, property of a Rigid Body (C-API)*/
PL_DECLARE_HANDLE(plCollisionShapeHandle);
/* Constraint for Rigid Bodies */
/** Constraint for Rigid Bodies (C-API)*/
PL_DECLARE_HANDLE(plConstraintHandle);
/* Triangle Mesh interface */
/** Triangle Mesh interface (C-API)*/
PL_DECLARE_HANDLE(plMeshInterfaceHandle);
/* Broadphase Scene/Proxy Handles */
/** Broadphase Scene/Proxy Handles (C-API)*/
PL_DECLARE_HANDLE(plCollisionBroadphaseHandle);
PL_DECLARE_HANDLE(plBroadphaseProxyHandle);
PL_DECLARE_HANDLE(plCollisionWorldHandle);
/*
/**
Create and Delete a Physics SDK
*/
extern plPhysicsSdkHandle plNewBulletSdk(); //this could be also another sdk, like ODE, PhysX etc.
extern void plDeletePhysicsSdk(plPhysicsSdkHandle physicsSdk);
/* Collision World, not strictly necessary, you can also just create a Dynamics World with Rigid Bodies which internally manages the Collision World with Collision Objects */
/** Collision World, not strictly necessary, you can also just create a Dynamics World with Rigid Bodies which internally manages the Collision World with Collision Objects */
typedef void(*btBroadphaseCallback)(void* clientData, void* object1,void* object2);

View File

@ -535,7 +535,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::removeHandle(BP_FP_INT_TYPE handle,bt
//explicitly remove the pairs containing the proxy
//we could do it also in the sortMinUp (passing true)
//todo: compare performance
///@todo: compare performance
if (!m_pairCache->hasDeferredRemoval())
{
m_pairCache->removeOverlappingPairsContainingProxy(pHandle,dispatcher);

View File

@ -579,7 +579,7 @@ DBVT_INLINE int Select( const btDbvtAabbMm& o,
{
#if DBVT_SELECT_IMPL == DBVT_IMPL_SSE
static DBVT_ALIGN const unsigned __int32 mask[]={0x7fffffff,0x7fffffff,0x7fffffff,0x7fffffff};
// TODO: the intrinsic version is 11% slower
///@todo: the intrinsic version is 11% slower
#if DBVT_USE_INTRINSIC_SSE
union btSSEUnion ///NOTE: if we use more intrinsics, move btSSEUnion into the LinearMath directory

View File

@ -46,7 +46,6 @@ btHashedOverlappingPairCache::btHashedOverlappingPairCache():
btHashedOverlappingPairCache::~btHashedOverlappingPairCache()
{
//todo/test: show we erase/delete data, or is it automatic
}
@ -517,7 +516,6 @@ btSortedOverlappingPairCache::btSortedOverlappingPairCache():
btSortedOverlappingPairCache::~btSortedOverlappingPairCache()
{
//todo/test: show we erase/delete data, or is it automatic
}
void btSortedOverlappingPairCache::cleanOverlappingPair(btBroadphasePair& pair,btDispatcher* dispatcher)

View File

@ -369,7 +369,7 @@ public:
btVector3 v = (point - m_bvhAabbMin) * m_bvhQuantization;
///Make sure rounding is done in a way that unQuantize(quantizeWithClamp(...)) is conservative
///end-points always set the first bit, so that they are sorted properly (so that neighbouring AABBs overlap properly)
///todo: double-check this
///@todo: double-check this
if (isMax)
{
out[0] = (unsigned short) (((unsigned short)(v.getX()+btScalar(1.)) | 1));

View File

@ -115,7 +115,7 @@ bool SphereTriangleDetector::collide(const btVector3& sphereCenter,btVector3 &po
normal *= btScalar(-1.);
}
///todo: move this gContactBreakingThreshold into a proper structure
///@todo: move this gContactBreakingThreshold into a proper structure
extern btScalar gContactBreakingThreshold;
btScalar contactMargin = gContactBreakingThreshold;

View File

@ -22,7 +22,7 @@ class btPoolAllocator;
///btCollisionConfiguration allows to configure Bullet collision detection
///stack allocator size, default collision algorithms and persistent manifold pool size
///todo: describe the meaning
///@todo: describe the meaning
class btCollisionConfiguration
{

View File

@ -380,7 +380,7 @@ void btCollisionWorld::rayTestSingle(const btTransform& rayFromTrans,const btTra
}
} else {
BT_PROFILE("rayTestCompound");
//todo: use AABB tree or other BVH acceleration structure!
///@todo: use AABB tree or other BVH acceleration structure, see btDbvt
if (collisionShape->isCompound())
{
const btCompoundShape* compoundShape = static_cast<const btCompoundShape*>(collisionShape);
@ -577,7 +577,7 @@ void btCollisionWorld::objectQuerySingle(const btConvexShape* castShape,const bt
triangleMesh->processAllTriangles(&tccb,rayAabbMinLocal,rayAabbMaxLocal);
}
} else {
//todo: use AABB tree or other BVH acceleration structure!
///@todo : use AABB tree or other BVH acceleration structure!
if (collisionShape->isCompound())
{
const btCompoundShape* compoundShape = static_cast<const btCompoundShape*>(collisionShape);

View File

@ -1,6 +1,6 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
Copyright (c) 2003-2006 Erwin Coumans http://bulletphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
@ -22,21 +22,21 @@ subject to the following restrictions:
*
* Bullet is a Collision Detection and Rigid Body Dynamics Library. The Library is Open Source and free for commercial use, under the ZLib license ( http://opensource.org/licenses/zlib-license.php ).
*
* There is the Physics Forum for Feedback and bteral Collision Detection and Physics discussions.
* Please visit http://www.continuousphysics.com/Bullet/phpBB2/index.php
* There is the Physics Forum for feedback and general Collision Detection and Physics discussions.
* Please visit http://www.bulletphysics.com
*
* @section install_sec Installation
*
* @subsection step1 Step 1: Download
* You can download the Bullet Physics Library from our website: http://www.continuousphysics.com/Bullet/
* You can download the Bullet Physics Library from the Google Code repository: http://code.google.com/p/bullet/downloads/list
* @subsection step2 Step 2: Building
* Bullet comes with autogenerated Project Files for Microsoft Visual Studio 6, 7, 7.1 and 8.
* The main Workspace/Solution is located in Bullet/msvc/8/wksbullet.sln (replace 8 with your version).
*
* Under other platforms, like Linux or Mac OS-X, Bullet can be build using either using make, cmake, http://www.cmake.org, or jam, http://www.perforce.com/jam/jam.html . cmake can autogenerate Xcode, KDevelop, MSVC and other build systems. just run cmake . in the root of Bullet.
* Under other platforms, like Linux or Mac OS-X, Bullet can be build using either using make, cmake, http://www.cmake.org , or jam, http://www.perforce.com/jam/jam.html . cmake can autogenerate Xcode, KDevelop, MSVC and other build systems. just run cmake . in the root of Bullet.
* So if you are not using MSVC or cmake, you can run ./autogen.sh ./configure to create both Makefile and Jamfile and then run make or jam.
* Jam is a build system that can build the library, demos and also autogenerate the MSVC Project Files.
* If you don't have jam installed, you can make jam from the included jam-2.5 sources, or download jam from ftp://ftp.perforce.com/pub/jam/
* If you don't have jam installed, you can make jam from the included jam-2.5 sources, or download jam from ftp://ftp.perforce.com/jam
*
* @subsection step3 Step 3: Testing demos
* Try to run and experiment with BasicDemo executable as a starting point.

View File

@ -38,7 +38,7 @@ subject to the following restrictions:
#include "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h"
@ -122,21 +122,6 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
{
#ifdef USE_BT_GJKEPA
btConvexShape* shape0(static_cast<btConvexShape*>(body0->getCollisionShape()));
btConvexShape* shape1(static_cast<btConvexShape*>(body1->getCollisionShape()));
const btScalar radialmargin(0/*shape0->getMargin()+shape1->getMargin()*/);
btGjkEpaSolver::sResults results;
if(btGjkEpaSolver::Collide( shape0,body0->getWorldTransform(),
shape1,body1->getWorldTransform(),
radialmargin,results))
{
dispatchInfo.m_debugDraw->drawLine(results.witnesses[1],results.witnesses[1]+results.normal,btVector3(255,0,0));
resultOut->addContactPoint(results.normal,results.witnesses[1],-results.depth);
}
#else
btGjkPairDetector::ClosestPointInput input;
@ -154,7 +139,7 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
input.m_transformB = body1->getWorldTransform();
gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
#endif
btScalar sepDist = gjkPairDetector.getCachedSeparatingDistance()+dispatchInfo.m_convexConservativeDistanceThreshold;

View File

@ -17,7 +17,6 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h"
#include "BulletMultiThreaded/SpuContactManifoldCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h"
@ -101,12 +100,10 @@ btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(const btDefault
int maxSize = sizeof(btConvexConvexAlgorithm);
int maxSize2 = sizeof(btConvexConcaveCollisionAlgorithm);
int maxSize3 = sizeof(btCompoundCollisionAlgorithm);
int maxSize4 = sizeof(SpuContactManifoldCollisionAlgorithm);
int sl = sizeof(btConvexSeparatingDistanceUtil);
sl = sizeof(btGjkPairDetector);
int collisionAlgorithmMaxElementSize = btMax(maxSize,maxSize2);
collisionAlgorithmMaxElementSize = btMax(collisionAlgorithmMaxElementSize,maxSize3);
collisionAlgorithmMaxElementSize = btMax(collisionAlgorithmMaxElementSize,maxSize4);
if (constructionInfo.m_stackAlloc)
{

View File

@ -44,7 +44,7 @@ struct btDefaultCollisionConstructionInfo
///btCollisionConfiguration allows to configure Bullet collision detection
///stack allocator, pool memory allocators
///todo: describe the meaning
///@todo: describe the meaning
class btDefaultCollisionConfiguration : public btCollisionConfiguration
{

View File

@ -118,7 +118,7 @@ public:
///btGhostPairCache keeps track of overlapping objects that have AABB overlap with the ghost
///The btGhostPairCallback interfaces and forwards adding and removal of overlapping pairs from the btBroadphaseInterface to btGhostObject.
class btGhostPairCallback : public btOverlappingPairCallback
{

View File

@ -93,7 +93,7 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
newPt.m_index0 = m_index0;
newPt.m_index1 = m_index1;
///todo, check this for any side effects
///@todo, check this for any side effects
if (insertIndex >= 0)
{
//const btManifoldPoint& oldPoint = m_manifoldPtr->getContactPoint(insertIndex);

View File

@ -262,7 +262,7 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher,btCollisio
btCollisionObject* colObj0 = static_cast<btCollisionObject*>(manifold->getBody0());
btCollisionObject* colObj1 = static_cast<btCollisionObject*>(manifold->getBody1());
//todo: check sleeping conditions!
///@todo: check sleeping conditions!
if (((colObj0) && colObj0->getActivationState() != ISLAND_SLEEPING) ||
((colObj1) && colObj1->getActivationState() != ISLAND_SLEEPING))
{
@ -287,9 +287,7 @@ void btSimulationIslandManager::buildIslands(btDispatcher* dispatcher,btCollisio
//
// todo: this is random access, it can be walked 'cache friendly'!
//
///@todo: this is random access, it can be walked 'cache friendly'!
void btSimulationIslandManager::buildAndProcessIslands(btDispatcher* dispatcher,btCollisionObjectArray& collisionObjects, IslandCallback* callback)
{

View File

@ -59,7 +59,7 @@ void btSphereTriangleCollisionAlgorithm::processCollision (btCollisionObject* co
SphereTriangleDetector detector(sphere,triangle);
btDiscreteCollisionDetectorInterface::ClosestPointInput input;
input.m_maximumDistanceSquared = btScalar(1e30);//todo: tighter bounds
input.m_maximumDistanceSquared = btScalar(1e30);///@todo: tighter bounds
input.m_transformA = sphereObj->getWorldTransform();
input.m_transformB = triObj->getWorldTransform();

View File

@ -65,7 +65,7 @@ void btCollisionShape::calculateTemporalAabb(const btTransform& curTrans,const b
// add linear motion
btVector3 linMotion = linvel*timeStep;
//todo: simd would have a vector max/min operation, instead of per-element access
///@todo: simd would have a vector max/min operation, instead of per-element access
if (linMotion.x() > btScalar(0.))
temporalAabbMaxx += linMotion.x();
else

View File

@ -24,8 +24,6 @@ subject to the following restrictions:
#include "btCollisionMargin.h"
#include "LinearMath/btAlignedAllocator.h"
//todo: get rid of this btConvexCastResult thing!
struct btConvexCastResult;
#define MAX_PREFERRED_PENETRATION_DIRECTIONS 10
/// The btConvexShape is an abstract shape interface, implemented by all convex shapes such as btBoxShape, btConvexHullShape etc.

View File

@ -108,7 +108,7 @@ void btConvexTriangleMeshShape::batchedUnitVectorGetSupportingVertexWithoutMargi
}
}
//todo: could do the batch inside the callback!
///@todo: could do the batch inside the callback!
for (int j=0;j<numVectors;j++)

View File

@ -186,7 +186,7 @@ void btHeightfieldTerrainShape::quantizeWithClamp(int* out, const btVector3& poi
btVector3 v = (clampedPoint);// - m_bvhAabbMin) * m_bvhQuantization;
//TODO: optimization: check out how to removed this btFabs
///@todo: optimization: check out how to removed this btFabs
out[0] = (int)(v.getX() + v.getX() / btFabs(v.getX())* btScalar(0.5) );
out[1] = (int)(v.getY() + v.getY() / btFabs(v.getY())* btScalar(0.5) );

View File

@ -35,7 +35,7 @@ btVector3 btMinkowskiSumShape::localGetSupportingVertexWithoutMargin(const btVec
void btMinkowskiSumShape::batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const
{
//todo: could make recursive use of batching. probably this shape is not used frequently.
///@todo: could make recursive use of batching. probably this shape is not used frequently.
for (int i=0;i<numVectors;i++)
{
supportVerticesOut[i] = localGetSupportingVertexWithoutMargin(vectors[i]);

View File

@ -28,7 +28,7 @@ struct btTriangle
int m_triangleIndex;
};
///btTriangleBuffer can be useful to collect and store overlapping triangles between AABB and concave objects that support 'processAllTriangles'
///The btTriangleBuffer callback can be useful to collect and store overlapping triangles between AABB and concave objects that support 'processAllTriangles'
///Example usage of this class:
/// btTriangleBuffer triBuf;
/// concaveShape->processAllTriangles(&triBuf,aabbMin, aabbMax);

View File

@ -78,7 +78,7 @@ void btTriangleMesh::addIndex(int index)
int btTriangleMesh::findOrAddVertex(const btVector3& vertex, bool removeDuplicateVertices)
{
//return index of new/existing vertex
//todo: could use acceleration structure for this
///@todo: could use acceleration structure for this
if (m_use4componentVertices)
{
if (removeDuplicateVertices)

View File

@ -26,9 +26,6 @@ subject to the following restrictions:
#include "LinearMath/btTransform.h"
/*! \defgroup BOUND_AABB_OPERATIONS
*/
//! @{
///Swap numbers
#define BT_SWAP_NUMBERS(a,b){ \
@ -646,6 +643,5 @@ SIMD_FORCE_INLINE bool btCompareTransformsEqual(const btTransform & t1,const btT
}
//! @}
#endif // GIM_BOX_COLLISION_H_INCLUDED

View File

@ -27,9 +27,6 @@ subject to the following restrictions:
#include "LinearMath/btTransform.h"
#include "LinearMath/btGeometryUtil.h"
/*! \addtogroup GEOMETRIC_OPERATIONS
*/
//! @{
SIMD_FORCE_INLINE btScalar bt_distance_point_plane(const btVector4 & plane,const btVector3 &point)
{
@ -181,6 +178,5 @@ SIMD_FORCE_INLINE int bt_plane_clip_triangle(
//! @}
#endif // GIM_TRI_COLLISION_H_INCLUDED

View File

@ -103,12 +103,12 @@ void btContactArray::merge_contacts(
push_back(contacts[keycontacts[0].m_value]);
BT_CONTACT * pcontact = &(*this)[0];
GIM_CONTACT * pcontact = &(*this)[0];
for( i=1;i<keycontacts.size();i++)
{
key = keycontacts[i].m_key;
const BT_CONTACT * scontact = &contacts[keycontacts[i].m_value];
const GIM_CONTACT * scontact = &contacts[keycontacts[i].m_value];
if(last_key == key)//same points
{
@ -158,7 +158,7 @@ void btContactArray::merge_contacts_unique(const btContactArray & contacts)
return;
}
BT_CONTACT average_contact = contacts[0];
GIM_CONTACT average_contact = contacts[0];
for (int i=1;i<contacts.size() ;i++ )
{

View File

@ -29,11 +29,6 @@ subject to the following restrictions:
#include "btTriangleShapeEx.h"
/*! \defgroup CONTACTS
\brief
Functions for managing and sorting contacts resulting from a collision query.
*/
//! @{
/**
Configuration var for applying interpolation of contact normals
@ -42,8 +37,9 @@ Configuration var for applying interpolation of contact normals
#define CONTACT_DIFF_EPSILON 0.00001f
/// Structure for collision results
class BT_CONTACT
///The GIM_CONTACT is an internal GIMPACT structure, similar to btManifoldPoint.
///@todo: remove and replace GIM_CONTACT by btManifoldPoint.
class GIM_CONTACT
{
public:
btVector3 m_point;
@ -53,11 +49,11 @@ public:
int m_feature1;//Face number
int m_feature2;//Face number
public:
BT_CONTACT()
GIM_CONTACT()
{
}
BT_CONTACT(const BT_CONTACT & contact):
GIM_CONTACT(const GIM_CONTACT & contact):
m_point(contact.m_point),
m_normal(contact.m_normal),
m_depth(contact.m_depth),
@ -66,7 +62,7 @@ public:
{
}
BT_CONTACT(const btVector3 &point,const btVector3 & normal,
GIM_CONTACT(const btVector3 &point,const btVector3 & normal,
btScalar depth, int feature1, int feature2):
m_point(point),
m_normal(normal),
@ -112,7 +108,7 @@ public:
};
class btContactArray:public btAlignedObjectArray<BT_CONTACT>
class btContactArray:public btAlignedObjectArray<GIM_CONTACT>
{
public:
btContactArray()
@ -124,11 +120,11 @@ public:
const btVector3 &point,const btVector3 & normal,
btScalar depth, int feature1, int feature2)
{
push_back( BT_CONTACT(point,normal,depth,feature1,feature2) );
push_back( GIM_CONTACT(point,normal,depth,feature1,feature2) );
}
SIMD_FORCE_INLINE void push_triangle_contacts(
const BT_TRIANGLE_CONTACT & tricontact,
const GIM_TRIANGLE_CONTACT & tricontact,
int feature1,int feature2)
{
for(int i = 0;i<tricontact.m_point_count ;i++ )
@ -145,5 +141,5 @@ public:
void merge_contacts_unique(const btContactArray & contacts);
};
//! @}
#endif // GIM_CONTACT_H_INCLUDED

View File

@ -65,7 +65,7 @@ float btGImpactBvh::getAverageTreeCollisionTime()
/////////////////////// btBvhTree /////////////////////////////////
int btBvhTree::_calc_splitting_axis(
BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
{
int i;
@ -97,7 +97,7 @@ int btBvhTree::_calc_splitting_axis(
int btBvhTree::_sort_and_calc_splitting_index(
BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex,
GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex,
int endIndex, int splitAxis)
{
int i;
@ -158,7 +158,7 @@ int btBvhTree::_sort_and_calc_splitting_index(
}
void btBvhTree::_build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
void btBvhTree::_build_sub_tree(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
{
int curIndex = m_num_nodes;
m_num_nodes++;
@ -211,7 +211,7 @@ void btBvhTree::_build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, int startIn
//! stackless build tree
void btBvhTree::build_tree(
BT_BVH_DATA_ARRAY & primitive_boxes)
GIM_BVH_DATA_ARRAY & primitive_boxes)
{
// initialize node count to 0
m_num_nodes = 0;
@ -236,7 +236,7 @@ void btGImpactBvh::refit()
}
else
{
//const BT_BVH_TREE_NODE * nodepointer = get_node_pointer(nodecount);
//const GIM_BVH_TREE_NODE * nodepointer = get_node_pointer(nodecount);
//get left bound
btAABB bound;
bound.invalidate();
@ -266,7 +266,7 @@ void btGImpactBvh::refit()
void btGImpactBvh::buildSet()
{
//obtain primitive boxes
BT_BVH_DATA_ARRAY primitive_boxes;
GIM_BVH_DATA_ARRAY primitive_boxes;
primitive_boxes.resize(m_primitive_manager->get_primitive_count());
for (int i = 0;i<primitive_boxes.size() ;i++ )

View File

@ -32,29 +32,23 @@ subject to the following restrictions:
/*! \defgroup BOX_TREES
*/
//! @{
//! Overlapping pair
struct BT_PAIR
struct GIM_PAIR
{
int m_index1;
int m_index2;
BT_PAIR()
GIM_PAIR()
{}
BT_PAIR(const BT_PAIR & p)
GIM_PAIR(const GIM_PAIR & p)
{
m_index1 = p.m_index1;
m_index2 = p.m_index2;
}
BT_PAIR(int index1, int index2)
GIM_PAIR(int index1, int index2)
{
m_index1 = index1;
m_index2 = index2;
@ -62,7 +56,7 @@ struct BT_PAIR
};
//! A pairset array
class btPairSet: public btAlignedObjectArray<BT_PAIR>
class btPairSet: public btAlignedObjectArray<GIM_PAIR>
{
public:
btPairSet()
@ -71,32 +65,32 @@ public:
}
inline void push_pair(int index1,int index2)
{
push_back(BT_PAIR(index1,index2));
push_back(GIM_PAIR(index1,index2));
}
inline void push_pair_inv(int index1,int index2)
{
push_back(BT_PAIR(index2,index1));
push_back(GIM_PAIR(index2,index1));
}
};
struct BT_BVH_DATA
///GIM_BVH_DATA is an internal GIMPACT collision structure to contain axis aligned bounding box
struct GIM_BVH_DATA
{
btAABB m_bound;
int m_data;
};
//! Node Structure for trees
class BT_BVH_TREE_NODE
class GIM_BVH_TREE_NODE
{
public:
btAABB m_bound;
protected:
int m_escapeIndexOrDataIndex;
public:
BT_BVH_TREE_NODE()
GIM_BVH_TREE_NODE()
{
m_escapeIndexOrDataIndex = 0;
}
@ -133,12 +127,12 @@ public:
};
class BT_BVH_DATA_ARRAY:public btAlignedObjectArray<BT_BVH_DATA>
class GIM_BVH_DATA_ARRAY:public btAlignedObjectArray<GIM_BVH_DATA>
{
};
class BT_BVH_TREE_NODE_ARRAY:public btAlignedObjectArray<BT_BVH_TREE_NODE>
class GIM_BVH_TREE_NODE_ARRAY:public btAlignedObjectArray<GIM_BVH_TREE_NODE>
{
};
@ -150,15 +144,15 @@ class btBvhTree
{
protected:
int m_num_nodes;
BT_BVH_TREE_NODE_ARRAY m_node_array;
GIM_BVH_TREE_NODE_ARRAY m_node_array;
protected:
int _sort_and_calc_splitting_index(
BT_BVH_DATA_ARRAY & primitive_boxes,
GIM_BVH_DATA_ARRAY & primitive_boxes,
int startIndex, int endIndex, int splitAxis);
int _calc_splitting_axis(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
int _calc_splitting_axis(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
void _build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
void _build_sub_tree(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
public:
btBvhTree()
{
@ -167,7 +161,7 @@ public:
//! prototype functions for box tree management
//!@{
void build_tree(BT_BVH_DATA_ARRAY & primitive_boxes);
void build_tree(GIM_BVH_DATA_ARRAY & primitive_boxes);
SIMD_FORCE_INLINE void clearNodes()
{
@ -218,7 +212,7 @@ public:
return m_node_array[nodeindex].getEscapeIndex();
}
SIMD_FORCE_INLINE const BT_BVH_TREE_NODE * get_node_pointer(int index = 0) const
SIMD_FORCE_INLINE const GIM_BVH_TREE_NODE * get_node_pointer(int index = 0) const
{
return &m_node_array[index];
}
@ -382,12 +376,11 @@ public:
}
SIMD_FORCE_INLINE const BT_BVH_TREE_NODE * get_node_pointer(int index = 0) const
SIMD_FORCE_INLINE const GIM_BVH_TREE_NODE * get_node_pointer(int index = 0) const
{
return m_box_tree.get_node_pointer(index);
}
//! @}
static float getAverageTreeCollisionTime();

View File

@ -404,7 +404,7 @@ void btGImpactCollisionAlgorithm::collide_sat_triangles(btCollisionObject * body
btPrimitiveTriangle ptri0;
btPrimitiveTriangle ptri1;
BT_TRIANGLE_CONTACT contact_data;
GIM_TRIANGLE_CONTACT contact_data;
shape0->lockChildShapes();
shape1->lockChildShapes();
@ -540,7 +540,7 @@ void btGImpactCollisionAlgorithm::gimpact_vs_gimpact(
int i = pairset.size();
while(i--)
{
BT_PAIR * pair = &pairset[i];
GIM_PAIR * pair = &pairset[i];
m_triface0 = pair->m_index1;
m_triface1 = pair->m_index2;
btCollisionShape * colshape0 = retriever0.getChildShape(m_triface0);

View File

@ -67,7 +67,7 @@ float btGImpactQuantizedBvh::getAverageTreeCollisionTime()
/////////////////////// btQuantizedBvhTree /////////////////////////////////
void btQuantizedBvhTree::calc_quantization(
BT_BVH_DATA_ARRAY & primitive_boxes, btScalar boundMargin)
GIM_BVH_DATA_ARRAY & primitive_boxes, btScalar boundMargin)
{
//calc globa box
btAABB global_bound;
@ -86,7 +86,7 @@ void btQuantizedBvhTree::calc_quantization(
int btQuantizedBvhTree::_calc_splitting_axis(
BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
{
int i;
@ -118,7 +118,7 @@ int btQuantizedBvhTree::_calc_splitting_axis(
int btQuantizedBvhTree::_sort_and_calc_splitting_index(
BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex,
GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex,
int endIndex, int splitAxis)
{
int i;
@ -179,7 +179,7 @@ int btQuantizedBvhTree::_sort_and_calc_splitting_index(
}
void btQuantizedBvhTree::_build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
void btQuantizedBvhTree::_build_sub_tree(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex)
{
int curIndex = m_num_nodes;
m_num_nodes++;
@ -232,7 +232,7 @@ void btQuantizedBvhTree::_build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, in
//! stackless build tree
void btQuantizedBvhTree::build_tree(
BT_BVH_DATA_ARRAY & primitive_boxes)
GIM_BVH_DATA_ARRAY & primitive_boxes)
{
calc_quantization(primitive_boxes);
// initialize node count to 0
@ -258,7 +258,7 @@ void btGImpactQuantizedBvh::refit()
}
else
{
//const BT_BVH_TREE_NODE * nodepointer = get_node_pointer(nodecount);
//const GIM_BVH_TREE_NODE * nodepointer = get_node_pointer(nodecount);
//get left bound
btAABB bound;
bound.invalidate();
@ -288,7 +288,7 @@ void btGImpactQuantizedBvh::refit()
void btGImpactQuantizedBvh::buildSet()
{
//obtain primitive boxes
BT_BVH_DATA_ARRAY primitive_boxes;
GIM_BVH_DATA_ARRAY primitive_boxes;
primitive_boxes.resize(m_primitive_manager->get_primitive_count());
for (int i = 0;i<primitive_boxes.size() ;i++ )

View File

@ -29,12 +29,6 @@ subject to the following restrictions:
/*! \defgroup BOX_TREES
*/
//! @{
///btQuantizedBvhNode is a compressed aabb node, 16 bytes.
@ -100,7 +94,7 @@ ATTRIBUTE_ALIGNED16 (struct) BT_QUANTIZED_BVH_NODE
class BT_QUANTIZED_BVH_NODE_ARRAY:public btAlignedObjectArray<BT_QUANTIZED_BVH_NODE>
class GIM_QUANTIZED_BVH_NODE_ARRAY:public btAlignedObjectArray<BT_QUANTIZED_BVH_NODE>
{
};
@ -112,19 +106,19 @@ class btQuantizedBvhTree
{
protected:
int m_num_nodes;
BT_QUANTIZED_BVH_NODE_ARRAY m_node_array;
GIM_QUANTIZED_BVH_NODE_ARRAY m_node_array;
btAABB m_global_bound;
btVector3 m_bvhQuantization;
protected:
void calc_quantization(BT_BVH_DATA_ARRAY & primitive_boxes, btScalar boundMargin = btScalar(1.0) );
void calc_quantization(GIM_BVH_DATA_ARRAY & primitive_boxes, btScalar boundMargin = btScalar(1.0) );
int _sort_and_calc_splitting_index(
BT_BVH_DATA_ARRAY & primitive_boxes,
GIM_BVH_DATA_ARRAY & primitive_boxes,
int startIndex, int endIndex, int splitAxis);
int _calc_splitting_axis(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
int _calc_splitting_axis(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
void _build_sub_tree(BT_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
void _build_sub_tree(GIM_BVH_DATA_ARRAY & primitive_boxes, int startIndex, int endIndex);
public:
btQuantizedBvhTree()
{
@ -133,7 +127,7 @@ public:
//! prototype functions for box tree management
//!@{
void build_tree(BT_BVH_DATA_ARRAY & primitive_boxes);
void build_tree(GIM_BVH_DATA_ARRAY & primitive_boxes);
SIMD_FORCE_INLINE void quantizePoint(
unsigned short * quantizedpoint, const btVector3 & point) const
@ -365,7 +359,6 @@ public:
return m_box_tree.get_node_pointer(index);
}
//! @}
static float getAverageTreeCollisionTime();

View File

@ -251,16 +251,16 @@ bool btGenericPoolAllocator::freeMemory(void * pointer)
#define BT_DEFAULT_POOL_ELEMENT_SIZE 8
// main allocator
class BT_STANDARD_ALLOCATOR: public btGenericPoolAllocator
class GIM_STANDARD_ALLOCATOR: public btGenericPoolAllocator
{
public:
BT_STANDARD_ALLOCATOR():btGenericPoolAllocator(BT_DEFAULT_POOL_ELEMENT_SIZE,BT_DEFAULT_POOL_SIZE)
GIM_STANDARD_ALLOCATOR():btGenericPoolAllocator(BT_DEFAULT_POOL_ELEMENT_SIZE,BT_DEFAULT_POOL_SIZE)
{
}
};
// global allocator
BT_STANDARD_ALLOCATOR g_main_allocator;
GIM_STANDARD_ALLOCATOR g_main_allocator;
void * btPoolAlloc(size_t size)

View File

@ -155,14 +155,9 @@ public:
/*! \defgroup POOL_MEMORY_FUNCTIONS
standar managed Memory functions. Memory pools are used.
*/
//! @{
void * btPoolAlloc(size_t size);
void * btPoolRealloc(void *ptr, size_t oldsize, size_t newsize);
void btPoolFree(void *ptr);
//! @}
#endif

View File

@ -29,9 +29,6 @@ subject to the following restrictions:
/*! \defgroup GEOMETRIC_OPERATIONS
*/
//! @{
#define PLANEDIREPSILON 0.0000001f
@ -210,7 +207,6 @@ SIMD_FORCE_INLINE void bt_segment_collision(
//! @}
#endif // GIM_VECTOR_H_INCLUDED

View File

@ -29,9 +29,6 @@ subject to the following restrictions:
/*! \defgroup GEOMETRIC_OPERATIONS
*/
//! @{
@ -86,7 +83,6 @@ SIMD_FORCE_INLINE btVector3 bt_unquantize(
return vecOut;
}
//! @}
#endif // GIM_VECTOR_H_INCLUDED

View File

@ -25,7 +25,7 @@ subject to the following restrictions:
void BT_TRIANGLE_CONTACT::merge_points(const btVector4 & plane,
void GIM_TRIANGLE_CONTACT::merge_points(const btVector4 & plane,
btScalar margin, const btVector3 * points, int point_count)
{
m_point_count = 0;
@ -123,7 +123,7 @@ int btPrimitiveTriangle::clip_triangle(btPrimitiveTriangle & other, btVector3 *
return clipped_count;
}
bool btPrimitiveTriangle::find_triangle_collision_clip_method(btPrimitiveTriangle & other, BT_TRIANGLE_CONTACT & contacts)
bool btPrimitiveTriangle::find_triangle_collision_clip_method(btPrimitiveTriangle & other, GIM_TRIANGLE_CONTACT & contacts)
{
btScalar margin = m_margin + other.m_margin;
@ -132,7 +132,7 @@ bool btPrimitiveTriangle::find_triangle_collision_clip_method(btPrimitiveTriangl
//create planes
// plane v vs U points
BT_TRIANGLE_CONTACT contacts1;
GIM_TRIANGLE_CONTACT contacts1;
contacts1.m_separating_normal = m_plane;
@ -152,7 +152,7 @@ bool btPrimitiveTriangle::find_triangle_collision_clip_method(btPrimitiveTriangl
//Clip tri1 by tri2 edges
BT_TRIANGLE_CONTACT contacts2;
GIM_TRIANGLE_CONTACT contacts2;
contacts2.m_separating_normal = other.m_plane;
clipped_count = other.clip_triangle(*this,clipped_points);

View File

@ -35,14 +35,14 @@ subject to the following restrictions:
#define MAX_TRI_CLIPPING 16
//! Structure for collision
struct BT_TRIANGLE_CONTACT
struct GIM_TRIANGLE_CONTACT
{
btScalar m_penetration_depth;
int m_point_count;
btVector4 m_separating_normal;
btVector3 m_points[MAX_TRI_CLIPPING];
SIMD_FORCE_INLINE void copy_from(const BT_TRIANGLE_CONTACT& other)
SIMD_FORCE_INLINE void copy_from(const GIM_TRIANGLE_CONTACT& other)
{
m_penetration_depth = other.m_penetration_depth;
m_separating_normal = other.m_separating_normal;
@ -54,11 +54,11 @@ struct BT_TRIANGLE_CONTACT
}
}
BT_TRIANGLE_CONTACT()
GIM_TRIANGLE_CONTACT()
{
}
BT_TRIANGLE_CONTACT(const BT_TRIANGLE_CONTACT& other)
GIM_TRIANGLE_CONTACT(const GIM_TRIANGLE_CONTACT& other)
{
copy_from(other);
}
@ -123,7 +123,7 @@ public:
/*!
\pre this triangle and other must have their triangles calculated
*/
bool find_triangle_collision_clip_method(btPrimitiveTriangle & other, BT_TRIANGLE_CONTACT & contacts);
bool find_triangle_collision_clip_method(btPrimitiveTriangle & other, GIM_TRIANGLE_CONTACT & contacts);
};

View File

@ -34,11 +34,6 @@ email: projectileman@yahoo.com
#include "gim_memory.h"
/*! \addtogroup CONTAINERS
\brief
Abstract class for template containers
*/
//! @{
#define GIM_ARRAY_GROW_INCREMENT 2
#define GIM_ARRAY_GROW_FACTOR 2
@ -321,11 +316,10 @@ public:
{
resizeData(m_size);
}
//!@}
};
//! @}

View File

@ -40,9 +40,6 @@ email: projectileman@yahoo.com
/*! \defgroup GEOMETRIC_OPERATIONS
*/
//! @{
#define PLANEDIREPSILON 0.0000001f
@ -541,7 +538,6 @@ SIMD_FORCE_INLINE void SORT_3_INDICES(
//! @}
#endif // GIM_VECTOR_H_INCLUDED

View File

@ -34,11 +34,6 @@ email: projectileman@yahoo.com
#include "gim_array.h"
/*! \addtogroup CONTAINERS
\brief
Abstract class for template containers
*/
//! @{
#define GUINT_BIT_COUNT 32
#define GUINT_EXPONENT 5
@ -122,7 +117,6 @@ public:
};
//! @}

View File

@ -35,9 +35,6 @@ email: projectileman@yahoo.com
#include "gim_basic_geometry_operations.h"
#include "LinearMath/btTransform.h"
/*! \defgroup BOUND_AABB_OPERATIONS
*/
//! @{
//SIMD_FORCE_INLINE bool test_cross_edge_box(
@ -589,6 +586,5 @@ SIMD_FORCE_INLINE bool btCompareTransformsEqual(const btTransform & t1,const btT
}
//! @}
#endif // GIM_BOX_COLLISION_H_INCLUDED

View File

@ -40,12 +40,6 @@ email: projectileman@yahoo.com
#include "gim_tri_collision.h"
/*! \defgroup BOX_PRUNNING
*/
//! @{
//! Overlapping pair
struct GIM_PAIR
@ -446,7 +440,6 @@ public:
m_primitive_manager.get_primitive_triangle(getNodeData(nodeindex),triangle);
}
//! @}
};
//! Class for Box Tree Sets

View File

@ -33,9 +33,6 @@ email: projectileman@yahoo.com
-----------------------------------------------------------------------------
*/
/*! \addtogroup GEOMETRIC_OPERATIONS
*/
//! @{
//! This function calcs the distance from a 3D plane
class DISTANCE_PLANE_3D_FUNC
@ -209,6 +206,5 @@ SIMD_FORCE_INLINE GUINT PLANE_CLIP_TRIANGLE3D(
}
//! @}
#endif // GIM_TRI_COLLISION_H_INCLUDED

View File

@ -36,17 +36,6 @@ email: projectileman@yahoo.com
#include "gim_radixsort.h"
#include "gim_array.h"
/*! \defgroup CONTACTS
\brief
Functions for managing and sorting contacts resulting from a collision query.
<ul>
<li> Contact lists must be create by calling \ref GIM_CREATE_CONTACT_LIST
<li> After querys, contact lists must be destroy by calling \ref GIM_DYNARRAY_DESTROY
<li> Contacts can be merge for avoid duplicate results by calling \ref gim_merge_contacts
</ul>
*/
//! @{
/**
Configuration var for applying interpolation of contact normals
@ -55,6 +44,10 @@ Configuration var for applying interpolation of contact normals
#define CONTACT_DIFF_EPSILON 0.00001f
/// Structure for collision results
///Functions for managing and sorting contacts resulting from a collision query.
///Contact lists must be create by calling \ref GIM_CREATE_CONTACT_LIST
///After querys, contact lists must be destroy by calling \ref GIM_DYNARRAY_DESTROY
///Contacts can be merge for avoid duplicate results by calling \ref gim_merge_contacts
class GIM_CONTACT
{
public:
@ -168,5 +161,4 @@ public:
void merge_contacts_unique(const gim_contact_array & contacts);
};
//! @}
#endif // GIM_CONTACT_H_INCLUDED

View File

@ -36,11 +36,7 @@ email: projectileman@yahoo.com
#include "gim_math.h"
/*! \defgroup GEOMETRIC_TYPES
\brief
Basic types and constants for geometry
*/
//! @{
//! Short Integer vector 2D
typedef GSHORT vec2s[2];
@ -95,7 +91,6 @@ typedef GREAL mat4f[4][4];
typedef GREAL quatf[4];
//typedef struct _aabb3f aabb3f;
//! @}

View File

@ -34,11 +34,6 @@ email: projectileman@yahoo.com
#include "gim_radixsort.h"
/*! \addtogroup CONTAINERS
\brief
Abstract class for collision objects
*/
//! @{
#define GIM_INVALID_HASH 0xffffffff //!< A very very high value
#define GIM_DEFAULT_HASH_TABLE_SIZE 380
@ -204,12 +199,7 @@ protected:
//SuperBufferedArray< _node_type > m_nodes;
bool m_sorted;
/*! \defgroup HASH_TABLE_STRUCTURES
\brief
Hash table data management. The hash table has the indices to the corresponding m_nodes array
*/
//! @{
///Hash table data management. The hash table has the indices to the corresponding m_nodes array
GUINT * m_hash_table;//!<
GUINT m_table_size;//!<
GUINT m_node_size;//!<
@ -459,13 +449,8 @@ protected:
}
//! @}
/*! \defgroup SORTED_ARRAY_STRUCTURES
\brief
Sorted array data management. The hash table has the indices to the corresponding m_nodes array
*/
//! @{
///Sorted array data management. The hash table has the indices to the corresponding m_nodes array
inline bool _erase_sorted(GUINT index)
{
if(index>=(GUINT)m_nodes.size()) return false;
@ -575,8 +560,7 @@ protected:
return GIM_INVALID_HASH;
}
//! @}
public:
@ -913,8 +897,6 @@ public:
};
//! @}
#endif // GIM_CONTAINERS_H_INCLUDED

View File

@ -40,11 +40,6 @@ email: projectileman@yahoo.com
/*! \defgroup VECTOR_OPERATIONS
T
Operations for vectors : vec2f,vec3f and vec4f
*/
//! @{
//! Zero out a 2D vector
#define VEC_ZERO_2(a) \
@ -446,13 +441,8 @@ Takes two vectors a, b, blends them together with s <=1 */
//! @}
/*! \defgroup MATRIX_OPERATIONS
Operations for matrices : mat2f, mat3f and mat4f
*/
//! @{
/// initialize matrix
#define IDENTIFY_MATRIX_3X3(m) \
@ -1579,6 +1569,5 @@ and m is a mat4f<br>
}\
//! @}
#endif // GIM_VECTOR_H_INCLUDED

View File

@ -35,13 +35,6 @@ email: projectileman@yahoo.com
#include "LinearMath/btScalar.h"
/*! \defgroup BASIC_TYPES
Basic types and constants
Conventions:
Types starting with G
Constants starting with G_
*/
//! @{
#define GREAL btScalar
#define GREAL2 double
@ -52,15 +45,7 @@ Constants starting with G_
#define GINT64 long long
#define GUINT64 unsigned long long
//! @}
/*! \defgroup BASIC_CONSTANTS
Basic constants
Conventions:
Types starting with G
Constants starting with G_
*/
//! @{
#define G_PI 3.14159265358979f
#define G_HALF_PI 1.5707963f
@ -73,14 +58,9 @@ Constants starting with G_
#define G_REAL_INFINITY FLT_MAX
#define G_SIGN_BITMASK 0x80000000
#define G_EPSILON SIMD_EPSILON
//! @}
/*! \defgroup SCALAR_TYPES
\brief
Precision type constants
*/
//! @{
enum GIM_SCALAR_TYPES
{
G_STYPE_REAL =0,
@ -92,12 +72,8 @@ enum GIM_SCALAR_TYPES
G_STYPE_INT64,
G_STYPE_UINT64
};
//! @}
/*! \defgroup MATH_FUNCTIONS
mathematical functions
*/
//! @{
#define G_DEGTORAD(X) ((X)*3.1415926f/180.0f)
#define G_RADTODEG(X) ((X)*180.0f/3.1415926f)
@ -176,6 +152,6 @@ inline GREAL gim_sqrt(GREAL f)
return r;
}
//! @}
#endif // GIM_MATH_H_INCLUDED

View File

@ -36,9 +36,6 @@ email: projectileman@yahoo.com
#include "gim_math.h"
#include <memory.h>
//#define PREFETCH 1
//! \defgroup PREFETCH
//! @{
#ifdef PREFETCH
#include <xmmintrin.h> // for prefetch
#define pfval 64
@ -53,13 +50,9 @@ email: projectileman@yahoo.com
//! Prefetch 128
#define pf2(_x,_i)
#endif
//! @}
/*! \defgroup ARRAY_UTILITIES
\brief
Functions for manip packed arrays of numbers
*/
//! @{
///Functions for manip packed arrays of numbers
#define GIM_COPY_ARRAYS(dest_array,source_array,element_count)\
{\
for (GUINT _i_=0;_i_<element_count ;++_i_)\
@ -92,50 +85,36 @@ Functions for manip packed arrays of numbers
array[_i_] = constant;\
}\
}\
//! @}
/*! \defgroup MEMORY_FUNCTION_PROTOTYPES
Function prototypes to allocate and free memory.
*/
//! @{
///Function prototypes to allocate and free memory.
typedef void * gim_alloc_function (size_t size);
typedef void * gim_alloca_function (size_t size);//Allocs on the heap
typedef void * gim_realloc_function (void *ptr, size_t oldsize, size_t newsize);
typedef void gim_free_function (void *ptr);
//! @}
/*! \defgroup MEMORY_FUNCTION_HANDLERS
\brief
Memory Function Handlers
set new memory management functions. if fn is 0, the default handlers are
used. */
//! @{
///Memory Function Handlers
///set new memory management functions. if fn is 0, the default handlers are used.
void gim_set_alloc_handler (gim_alloc_function *fn);
void gim_set_alloca_handler (gim_alloca_function *fn);
void gim_set_realloc_handler (gim_realloc_function *fn);
void gim_set_free_handler (gim_free_function *fn);
//! @}
/*! \defgroup MEMORY_FUNCTION_GET_HANDLERS
\brief
get current memory management functions.
*/
//! @{
///get current memory management functions.
gim_alloc_function *gim_get_alloc_handler (void);
gim_alloca_function *gim_get_alloca_handler(void);
gim_realloc_function *gim_get_realloc_handler (void);
gim_free_function *gim_get_free_handler (void);
//! @}
/*! \defgroup MEMORY_FUNCTIONS
Standar Memory functions
*/
//! @{
///Standar Memory functions
void * gim_alloc(size_t size);
void * gim_alloca(size_t size);
void * gim_realloc(void *ptr, size_t oldsize, size_t newsize);
void gim_free(void *ptr);
//! @}
#if defined (WIN32) && !defined(__MINGW32__) && !defined(__CYGWIN__)

View File

@ -36,11 +36,7 @@ email: projectileman@yahoo.com
#include "gim_memory.h"
/*! \defgroup SORTING
\brief
Macros for sorting.
*/
///Macros for sorting.
//! Prototype for comparators
class less_comparator
{
@ -406,5 +402,5 @@ void gim_heap_sort(T *pArr, GUINT element_count, COMP_CLASS CompareFunc)
//! @}
#endif // GIM_RADIXSORT_H_INCLUDED

View File

@ -38,7 +38,7 @@ email: projectileman@yahoo.com
#define MIN_EDGE_EDGE_DIS 0.00001f
class _GIM_TRIANGLE_CALCULATION_CACHE
class GIM_TRIANGLE_CALCULATION_CACHE
{
public:
GREAL margin;
@ -489,7 +489,7 @@ public:
};
/*class _GIM_TRIANGLE_CALCULATION_CACHE
/*class GIM_TRIANGLE_CALCULATION_CACHE
{
public:
GREAL margin;
@ -627,7 +627,7 @@ bool GIM_TRIANGLE::collide_triangle_hard_test(
const GIM_TRIANGLE & other,
GIM_TRIANGLE_CONTACT_DATA & contact_data) const
{
_GIM_TRIANGLE_CALCULATION_CACHE calc_cache;
GIM_TRIANGLE_CALCULATION_CACHE calc_cache;
return calc_cache.triangle_collision(
m_vertices[0],m_vertices[1],m_vertices[2],m_margin,
other.m_vertices[0],other.m_vertices[1],other.m_vertices[2],other.m_margin,

View File

@ -36,9 +36,6 @@ email: projectileman@yahoo.com
#include "gim_box_collision.h"
#include "gim_clip_polygon.h"
/*! \addtogroup GEOMETRIC_OPERATIONS
*/
//! @{
@ -378,6 +375,5 @@ if 0.0<= u+v <=1.0 then they are inside of triangle
//! @}
#endif // GIM_TRI_COLLISION_H_INCLUDED

View File

@ -1,628 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the
use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it
freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not
claim that you wrote the original software. If you use this software in a
product, an acknowledgment in the product documentation would be appreciated
but is not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
/*
GJK-EPA collision solver by Nathanael Presson
Nov.2006
*/
#include "btGjkEpa.h"
#include <string.h> //for memset
#include "LinearMath/btStackAlloc.h"
#if defined(DEBUG) || defined (_DEBUG)
#include <stdio.h> //for debug printf
#ifdef __SPU__
#include <spu_printf.h>
#define printf spu_printf
#endif //__SPU__
#endif
namespace gjkepa_impl
{
//
// Port. typedefs
//
typedef btScalar F;
typedef bool Z;
typedef int I;
typedef unsigned int U;
typedef unsigned char U1;
typedef unsigned short U2;
typedef btVector3 Vector3;
typedef btMatrix3x3 Rotation;
//
// Config
//
#if 0
#define BTLOCALSUPPORT localGetSupportingVertexWithoutMargin
#else
#define BTLOCALSUPPORT localGetSupportingVertex
#endif
//
// Const
//
#define cstInf SIMD_INFINITY
#define cstPi SIMD_PI
#define cst2Pi SIMD_2_PI
#define GJK_maxiterations (128)
#define GJK_hashsize (1<<6)
#define GJK_hashmask (GJK_hashsize-1)
#define GJK_insimplex_eps F(0.0001)
#define GJK_sqinsimplex_eps (GJK_insimplex_eps*GJK_insimplex_eps)
#define EPA_maxiterations 256
#define EPA_inface_eps F(0.01)
#define EPA_accuracy F(0.001)
//
// Utils
//
static inline F Abs(F v) { return(v<0?-v:v); }
static inline F Sign(F v) { return(F(v<0?-1:1)); }
template <typename T> static inline void Swap(T& a,T& b) { T
t(a);a=b;b=t; }
template <typename T> static inline T Min(const T& a,const T& b) {
return(a<b?a:b); }
template <typename T> static inline T Max(const T& a,const T& b) {
return(a>b?a:b); }
static inline void ClearMemory(void* p,U sz) { memset(p,0,(size_t)sz);
}
#if 0
template <typename T> static inline void Raise(const T& object) {
throw(object); }
#else
template <typename T> static inline void Raise(const T&) {}
#endif
//
// GJK
//
struct GJK
{
struct Mkv
{
Vector3 w; /* Minkowski vertice */
Vector3 r; /* Ray */
};
struct He
{
Vector3 v;
He* n;
};
btStackAlloc* sa;
btBlock* sablock;
He* table[GJK_hashsize];
Rotation wrotations[2];
Vector3 positions[2];
const btConvexShape* shapes[2];
Mkv simplex[5];
Vector3 ray;
U order;
U iterations;
F margin;
Z failed;
//
GJK(btStackAlloc* psa,
const Rotation& wrot0,const Vector3& pos0,const btConvexShape* shape0,
const Rotation& wrot1,const Vector3& pos1,const btConvexShape* shape1,
F pmargin=0)
{
wrotations[0]=wrot0;positions[0]=pos0;shapes[0]=shape0;
wrotations[1]=wrot1;positions[1]=pos1;shapes[1]=shape1;
sa =psa;
sablock =sa->beginBlock();
margin =pmargin;
failed =false;
}
//
~GJK()
{
sa->endBlock(sablock);
}
// vdh : very dumm hash
static inline U Hash(const Vector3& v)
{
//this doesn't compile under GCC 3.3.5, so add the ()...
//const U h(U(v[0]*15461)^U(v[1]*83003)^U(v[2]*15473));
//return(((*((const U*)&h))*169639)&GJK_hashmask);
const U h((U)(v[0]*15461)^(U)(v[1]*83003)^(U)(v[2]*15473));
return(((*((const U*)&h))*169639)&GJK_hashmask);
}
//
inline Vector3 LocalSupport(const Vector3& d,U i) const
{
return(wrotations[i]*shapes[i]->BTLOCALSUPPORT(d*wrotations[i])+positions[i]);
}
//
inline void Support(const Vector3& d,Mkv& v) const
{
v.r = d;
v.w = LocalSupport(d,0)-LocalSupport(-d,1)+d*margin;
}
#define SPX(_i_) simplex[_i_]
#define SPXW(_i_) simplex[_i_].w
//
inline Z FetchSupport()
{
const U h(Hash(ray));
He* e = (He*)(table[h]);
while(e) { if(e->v==ray) { --order;return(false); } else e=e->n; }
e=(He*)sa->allocate(sizeof(He));e->v=ray;e->n=table[h];table[h]=e;
Support(ray,simplex[++order]);
return(ray.dot(SPXW(order))>0);
}
//
inline Z SolveSimplex2(const Vector3& ao,const Vector3& ab)
{
if(ab.dot(ao)>=0)
{
const Vector3 cabo(cross(ab,ao));
if(cabo.length2()>GJK_sqinsimplex_eps)
{ ray=cross(cabo,ab); }
else
{ return(true); }
}
else
{ order=0;SPX(0)=SPX(1);ray=ao; }
return(false);
}
//
inline Z SolveSimplex3(const Vector3& ao,const Vector3& ab,const Vector3&
ac)
{
return(SolveSimplex3a(ao,ab,ac,cross(ab,ac)));
}
//
inline Z SolveSimplex3a(const Vector3& ao,const Vector3& ab,const Vector3&
ac,const Vector3& cabc)
{
if((cross(cabc,ab)).dot(ao)<-GJK_insimplex_eps)
{ order=1;SPX(0)=SPX(1);SPX(1)=SPX(2);return(SolveSimplex2(ao,ab)); }
else if((cross(cabc,ac)).dot(ao)>+GJK_insimplex_eps)
{ order=1;SPX(1)=SPX(2);return(SolveSimplex2(ao,ac)); }
else
{
const F d(cabc.dot(ao));
if(Abs(d)>GJK_insimplex_eps)
{
if(d>0)
{ ray=cabc; }
else
{ ray=-cabc;Swap(SPX(0),SPX(1)); }
return(false);
} else return(true);
}
}
//
inline Z SolveSimplex4(const Vector3& ao,const Vector3& ab,const Vector3&
ac,const Vector3& ad)
{
Vector3 crs;
if((crs=cross(ab,ac)).dot(ao)>GJK_insimplex_eps)
{
order=2;SPX(0)=SPX(1);SPX(1)=SPX(2);SPX(2)=SPX(3);return(SolveSimplex3a(ao,ab,ac,crs));
}
else if((crs=cross(ac,ad)).dot(ao)>GJK_insimplex_eps)
{ order=2;SPX(2)=SPX(3);return(SolveSimplex3a(ao,ac,ad,crs)); }
else if((crs=cross(ad,ab)).dot(ao)>GJK_insimplex_eps)
{
order=2;SPX(1)=SPX(0);SPX(0)=SPX(2);SPX(2)=SPX(3);return(SolveSimplex3a(ao,ad,ab,crs));
}
else return(true);
}
//
inline Z SearchOrigin(const Vector3& initray=Vector3(1,0,0))
{
iterations = 0;
order = (U)-1;
failed = false;
ray = initray.normalized();
ClearMemory(table,sizeof(void*)*GJK_hashsize);
FetchSupport();
ray = -SPXW(0);
for(;iterations<GJK_maxiterations;++iterations)
{
const F rl(ray.length());
ray/=rl>0?rl:1;
if(FetchSupport())
{
Z found(false);
switch(order)
{
case 1: found=SolveSimplex2(-SPXW(1),SPXW(0)-SPXW(1));break;
case 2: found=SolveSimplex3(-SPXW(2),SPXW(1)-SPXW(2),SPXW(0)-SPXW(2));break;
case 3: found=SolveSimplex4(-SPXW(3),SPXW(2)-SPXW(3),SPXW(1)-SPXW(3),SPXW(0)-SPXW(3));break;
}
if(found) return(true);
} else return(false);
}
failed=true;
return(false);
}
//
inline Z EncloseOrigin()
{
switch(order)
{
/* Point */
case 0: break;
/* Line */
case 1:
{
const Vector3 ab(SPXW(1)-SPXW(0));
const Vector3 b[]={ cross(ab,Vector3(1,0,0)),
cross(ab,Vector3(0,1,0)),
cross(ab,Vector3(0,0,1))};
const F m[]={b[0].length2(),b[1].length2(),b[2].length2()};
const Rotation r(btQuaternion(ab.normalized(),cst2Pi/3));
Vector3 w(b[m[0]>m[1]?m[0]>m[2]?0:2:m[1]>m[2]?1:2]);
Support(w.normalized(),simplex[4]);w=r*w;
Support(w.normalized(),simplex[2]);w=r*w;
Support(w.normalized(),simplex[3]);w=r*w;
order=4;
return(true);
}
break;
/* Triangle */
case 2:
{
const
Vector3 n(cross((SPXW(1)-SPXW(0)),(SPXW(2)-SPXW(0))).normalized());
Support( n,simplex[3]);
Support(-n,simplex[4]);
order=4;
return(true);
}
break;
/* Tetrahedron */
case 3: return(true);
/* Hexahedron */
case 4: return(true);
}
return(false);
}
#undef SPX
#undef SPXW
};
//
// EPA
//
struct EPA
{
//
struct Face
{
const GJK::Mkv* v[3];
Face* f[3];
U e[3];
Vector3 n;
F d;
U mark;
Face* prev;
Face* next;
Face() {}
};
//
GJK* gjk;
btStackAlloc* sa;
Face* root;
U nfaces;
U iterations;
Vector3 features[2][3];
Vector3 nearest[2];
Vector3 normal;
F depth;
Z failed;
//
EPA(GJK* pgjk)
{
gjk = pgjk;
sa = pgjk->sa;
}
//
~EPA()
{
}
//
inline Vector3 GetCoordinates(const Face* face) const
{
const Vector3 o(face->n*-face->d);
const F a[]={ cross(face->v[0]->w-o,face->v[1]->w-o).length(),
cross(face->v[1]->w-o,face->v[2]->w-o).length(),
cross(face->v[2]->w-o,face->v[0]->w-o).length()};
const F sm(a[0]+a[1]+a[2]);
return(Vector3(a[1],a[2],a[0])/(sm>0?sm:1));
}
//
inline Face* FindBest() const
{
Face* bf = 0;
if(root)
{
Face* cf = root;
F bd(cstInf);
do {
if(cf->d<bd) { bd=cf->d;bf=cf; }
} while(0!=(cf=cf->next));
}
return(bf);
}
//
inline Z Set(Face* f,const GJK::Mkv* a,const GJK::Mkv* b,const GJK::Mkv*
c) const
{
const Vector3 nrm(cross(b->w-a->w,c->w-a->w));
const F len(nrm.length());
const Z valid( (cross(a->w,b->w).dot(nrm)>=-EPA_inface_eps)&&
(cross(b->w,c->w).dot(nrm)>=-EPA_inface_eps)&&
(cross(c->w,a->w).dot(nrm)>=-EPA_inface_eps));
f->v[0] = a;
f->v[1] = b;
f->v[2] = c;
f->mark = 0;
f->n = nrm/(len>0?len:cstInf);
f->d = Max<F>(0,-f->n.dot(a->w));
return(valid);
}
//
inline Face* NewFace(const GJK::Mkv* a,const GJK::Mkv* b,const GJK::Mkv* c)
{
Face* pf = (Face*)sa->allocate(sizeof(Face));
if(Set(pf,a,b,c))
{
if(root) root->prev=pf;
pf->prev=0;
pf->next=root;
root =pf;
++nfaces;
}
else
{
pf->prev=pf->next=0;
}
return(pf);
}
//
inline void Detach(Face* face)
{
if(face->prev||face->next)
{
--nfaces;
if(face==root)
{ root=face->next;root->prev=0; }
else
{
if(face->next==0)
{ face->prev->next=0; }
else
{ face->prev->next=face->next;face->next->prev=face->prev; }
}
face->prev=face->next=0;
}
}
//
inline void Link(Face* f0,U e0,Face* f1,U e1) const
{
f0->f[e0]=f1;f1->e[e1]=e0;
f1->f[e1]=f0;f0->e[e0]=e1;
}
//
GJK::Mkv* Support(const Vector3& w) const
{
GJK::Mkv* v =(GJK::Mkv*)sa->allocate(sizeof(GJK::Mkv));
gjk->Support(w,*v);
return(v);
}
//
U BuildHorizon(U markid,const GJK::Mkv* w,Face& f,U e,Face*& cf,Face*&
ff)
{
static const U mod3[]={0,1,2,0,1};
U ne(0);
if(f.mark!=markid)
{
const U e1(mod3[e+1]);
if((f.n.dot(w->w)+f.d)>0)
{
Face* nf = NewFace(f.v[e1],f.v[e],w);
Link(nf,0,&f,e);
if(cf) Link(cf,1,nf,2); else ff=nf;
cf=nf;ne=1;
}
else
{
const U e2(mod3[e+2]);
Detach(&f);
f.mark = markid;
ne += BuildHorizon(markid,w,*f.f[e1],f.e[e1],cf,ff);
ne += BuildHorizon(markid,w,*f.f[e2],f.e[e2],cf,ff);
}
}
return(ne);
}
//
inline F EvaluatePD(F accuracy=EPA_accuracy)
{
btBlock* sablock = sa->beginBlock();
Face* bestface = 0;
U markid(1);
depth = -cstInf;
normal = Vector3(0,0,0);
root = 0;
nfaces = 0;
iterations = 0;
failed = false;
/* Prepare hull */
if(gjk->EncloseOrigin())
{
const U* pfidx = 0;
U nfidx= 0;
const U* peidx = 0;
U neidx = 0;
GJK::Mkv* basemkv[5];
Face* basefaces[6];
switch(gjk->order)
{
/* Tetrahedron */
case 3: {
static const U fidx[4][3]={{2,1,0},{3,0,1},{3,1,2},{3,2,0}};
static const
U eidx[6][4]={{0,0,2,1},{0,1,1,1},{0,2,3,1},{1,0,3,2},{2,0,1,2},{3,0,2,2}};
pfidx=(const U*)fidx;nfidx=4;peidx=(const U*)eidx;neidx=6;
} break;
/* Hexahedron */
case 4: {
static const
U fidx[6][3]={{2,0,4},{4,1,2},{1,4,0},{0,3,1},{0,2,3},{1,3,2}};
static const
U eidx[9][4]={{0,0,4,0},{0,1,2,1},{0,2,1,2},{1,1,5,2},{1,0,2,0},{2,2,3,2},{3,1,5,0},{3,0,4,2},{5,1,4,1}};
pfidx=(const U*)fidx;nfidx=6;peidx=(const U*)eidx;neidx=9;
} break;
}
U i;
for( i=0;i<=gjk->order;++i) {
basemkv[i]=(GJK::Mkv*)sa->allocate(sizeof(GJK::Mkv));*basemkv[i]=gjk->simplex[i];
}
for( i=0;i<nfidx;++i,pfidx+=3) {
basefaces[i]=NewFace(basemkv[pfidx[0]],basemkv[pfidx[1]],basemkv[pfidx[2]]);
}
for( i=0;i<neidx;++i,peidx+=4) {
Link(basefaces[peidx[0]],peidx[1],basefaces[peidx[2]],peidx[3]); }
}
if(0==nfaces)
{
sa->endBlock(sablock);
return(depth);
}
/* Expand hull */
for(;iterations<EPA_maxiterations;++iterations)
{
Face* bf = FindBest();
if(bf)
{
GJK::Mkv* w = Support(-bf->n);
const F d(bf->n.dot(w->w)+bf->d);
bestface = bf;
if(d<-accuracy)
{
Face* cf =0;
Face* ff =0;
U nf = 0;
Detach(bf);
bf->mark=++markid;
for(U i=0;i<3;++i) {
nf+=BuildHorizon(markid,w,*bf->f[i],bf->e[i],cf,ff); }
if(nf<=2) { break; }
Link(cf,1,ff,2);
} else break;
} else break;
}
/* Extract contact */
if(bestface)
{
const Vector3 b(GetCoordinates(bestface));
normal = bestface->n;
depth = Max<F>(0,bestface->d);
for(U i=0;i<2;++i)
{
const F s(F(i?-1:1));
for(U j=0;j<3;++j)
{
features[i][j]=gjk->LocalSupport(s*bestface->v[j]->r,i);
}
}
nearest[0] = features[0][0]*b.x()+features[0][1]*b.y()+features[0][2]*b.z();
nearest[1] = features[1][0]*b.x()+features[1][1]*b.y()+features[1][2]*b.z();
} else failed=true;
sa->endBlock(sablock);
return(depth);
}
};
}
//
// Api
//
using namespace gjkepa_impl;
//
bool btGjkEpaSolver::Collide(const btConvexShape *shape0,const btTransform &wtrs0,
const btConvexShape *shape1,const btTransform &wtrs1,
btScalar radialmargin,
btStackAlloc* stackAlloc,
sResults& results)
{
/* Initialize */
results.witnesses[0] =
results.witnesses[1] =
results.normal = Vector3(0,0,0);
results.depth = 0;
results.status = sResults::Separated;
results.epa_iterations = 0;
results.gjk_iterations = 0;
/* Use GJK to locate origin */
GJK gjk(stackAlloc,
wtrs0.getBasis(),wtrs0.getOrigin(),shape0,
wtrs1.getBasis(),wtrs1.getOrigin(),shape1,
radialmargin+EPA_accuracy);
const Z collide(gjk.SearchOrigin());
results.gjk_iterations = static_cast<int>(gjk.iterations+1);
if(collide)
{
/* Then EPA for penetration depth */
EPA epa(&gjk);
const F pd(epa.EvaluatePD());
results.epa_iterations = static_cast<int>(epa.iterations+1);
if(pd>0)
{
results.status = sResults::Penetrating;
results.normal = epa.normal;
results.depth = pd;
results.witnesses[0] = epa.nearest[0];
results.witnesses[1] = epa.nearest[1];
return(true);
} else { if(epa.failed) results.status=sResults::EPA_Failed; }
} else { if(gjk.failed) results.status=sResults::GJK_Failed; }
return(false);
}

View File

@ -1,53 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
/*
GJK-EPA collision solver by Nathanael Presson
Nov.2006
*/
#ifndef _05E48D53_04E0_49ad_BB0A_D74FE62E7366_
#define _05E48D53_04E0_49ad_BB0A_D74FE62E7366_
#include "BulletCollision/CollisionShapes/btConvexShape.h"
class btStackAlloc;
///btGjkEpaSolver contributed under zlib by Nathanael Presson
struct btGjkEpaSolver
{
struct sResults
{
enum eStatus
{
Separated, /* Shapes doesnt penetrate */
Penetrating, /* Shapes are penetrating */
GJK_Failed, /* GJK phase fail, no big issue, shapes are probably just 'touching' */
EPA_Failed /* EPA phase fail, bigger problem, need to save parameters, and debug */
} status;
btVector3 witnesses[2];
btVector3 normal;
btScalar depth;
int epa_iterations;
int gjk_iterations;
};
static bool Collide(const btConvexShape* shape0,const btTransform& wtrs0,
const btConvexShape* shape1,const btTransform& wtrs1,
btScalar radialmargin,
btStackAlloc* stackAlloc,
sResults& results);
};
#endif

View File

@ -18,13 +18,6 @@ subject to the following restrictions:
#include "BulletCollision/CollisionShapes/btConvexShape.h"
#include "btGjkEpaPenetrationDepthSolver.h"
#ifndef __SPU__
//#define USE_ORIGINAL_GJK 1
#endif
#ifdef USE_ORIGINAL_GJK
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa.h"
#endif
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
@ -41,20 +34,12 @@ bool btGjkEpaPenetrationDepthSolver::calcPenDepth( btSimplexSolverInterface& sim
const btScalar radialmargin(btScalar(0.));
//#define USE_ORIGINAL_GJK 1
#ifdef USE_ORIGINAL_GJK
btGjkEpaSolver::sResults results;
if(btGjkEpaSolver::Collide( pConvexA,transformA,
pConvexB,transformB,
radialmargin,stackAlloc,results))
#else
btVector3 guessVector(transformA.getOrigin()-transformB.getOrigin());
btGjkEpaSolver2::sResults results;
if(btGjkEpaSolver2::Penetration(pConvexA,transformA,
pConvexB,transformB,
guessVector,results))
#endif
{
// debugDraw->drawLine(results.witnesses[1],results.witnesses[1]+results.normal,btVector3(255,0,0));
//resultOut->addContactPoint(results.normal,results.witnesses[1],-results.depth);

View File

@ -106,7 +106,7 @@ public:
return m_pointCache[index];
}
/// todo: get this margin from the current physics / collision environment
///@todo: get this margin from the current physics / collision environment
btScalar getContactBreakingThreshold() const;
int getCacheEntry(const btManifoldPoint& newPoint) const;

View File

@ -16,7 +16,7 @@ subject to the following restrictions:
#ifndef CONTACT_CONSTRAINT_H
#define CONTACT_CONSTRAINT_H
//todo: make into a proper class working with the iterative constraint solver
///@todo: make into a proper class working with the iterative constraint solver
class btRigidBody;
#include "LinearMath/btVector3.h"

View File

@ -156,7 +156,7 @@ btScalar btRotationalLimitMotor::solveAngularLimits(
// clip correction impulse
btScalar clippedMotorImpulse;
//todo: should clip against accumulated impulse
///@todo: should clip against accumulated impulse
if (unclippedMotorImpulse>0.0f)
{
clippedMotorImpulse = unclippedMotorImpulse > maxMotorForce? maxMotorForce: unclippedMotorImpulse;

View File

@ -323,7 +323,6 @@ void btHingeConstraint::solveConstraint(btScalar timeStep)
btScalar denom = getRigidBodyA().computeAngularImpulseDenominator(normal) +
getRigidBodyB().computeAngularImpulseDenominator(normal);
// scale for mass and relaxation
//todo: expose this 0.9 factor to developer
velrelOrthog *= (btScalar(1.)/denom) * m_relaxationFactor;
}

View File

@ -840,7 +840,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
int numConstraintPool = m_tmpSolverConstraintPool.size();
int numFrictionPool = m_tmpSolverFrictionConstraintPool.size();
///todo: use stack allocator for such temporarily memory, same for solver bodies/constraints
///@todo: use stack allocator for such temporarily memory, same for solver bodies/constraints
m_orderTmpConstraintPool.resize(numConstraintPool);
m_orderFrictionConstraintPool.resize(numFrictionPool);
{

View File

@ -23,10 +23,10 @@ class btIDebugDraw;
#include "btSolverConstraint.h"
/// btSequentialImpulseConstraintSolver uses a Propagation Method and Sequentially applies impulses
/// The approach is the 3D version of Erin Catto's GDC 2006 tutorial. See http://www.gphysics.com
/// Although Sequential Impulse is more intuitive, it is mathematically equivalent to Projected Successive Overrelaxation (iterative LCP)
/// Applies impulses for combined restitution and penetration recovery and to simulate friction
///The btSequentialImpulseConstraintSolver uses a Propagation Method and Sequentially applies impulses
///The approach is the 3D version of Erin Catto's GDC 2006 tutorial. See http://www.gphysics.com
///Although Sequential Impulse is more intuitive, it is mathematically equivalent to Projected Successive Overrelaxation (iterative LCP)
///Applies impulses for combined restitution and penetration recovery and to simulate friction
class btSequentialImpulseConstraintSolver : public btConstraintSolver
{

View File

@ -24,7 +24,7 @@ class btRigidBody;
#include "LinearMath/btTransformUtil.h"
///btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packed to increase cache coherence/performance.
///The btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packed to increase cache coherence/performance.
ATTRIBUTE_ALIGNED16 (struct) btSolverBody
{
BT_DECLARE_ALIGNED_ALLOCATOR();

View File

@ -38,7 +38,7 @@ subject to the following restrictions:
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h"
#include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h"
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"

View File

@ -221,7 +221,7 @@ void btDiscreteDynamicsWorld::debugDrawWorld()
void btDiscreteDynamicsWorld::clearForces()
{
//todo: iterate over awake simulation islands!
///@todo: iterate over awake simulation islands!
for ( int i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];
@ -237,7 +237,7 @@ void btDiscreteDynamicsWorld::clearForces()
///apply gravity, call this once per timestep
void btDiscreteDynamicsWorld::applyGravity()
{
//todo: iterate over awake simulation islands!
///@todo: iterate over awake simulation islands!
for ( int i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];
@ -266,7 +266,7 @@ void btDiscreteDynamicsWorld::synchronizeMotionStates()
{
//we need to call the update at least once, even for sleeping objects
//otherwise the 'graphics' transform never updates properly
//so todo: add 'dirty' flag
///@todo: add 'dirty' flag
//if (body->getActivationState() != ISLAND_SLEEPING)
{
btTransform interpolatedTransform;
@ -1106,7 +1106,7 @@ void btDiscreteDynamicsWorld::debugDrawObject(const btTransform& worldTransform,
{
btConcaveShape* concaveMesh = (btConcaveShape*) shape;
//todo pass camera, for some culling
///@todo pass camera, for some culling? no -> we are not a graphics lib
btVector3 aabbMax(btScalar(1e30),btScalar(1e30),btScalar(1e30));
btVector3 aabbMin(btScalar(-1e30),btScalar(-1e30),btScalar(-1e30));

View File

@ -30,7 +30,7 @@ extern btScalar gDeactivationTime;
extern bool gDisableDeactivation;
///btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape.
///The btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape.
///It is recommended for performance and memory use to share btCollisionShape objects whenever possible.
///There are 3 types of rigid bodies:
///- A) Dynamic rigid bodies, with positive mass. Motion is controlled by rigid body dynamics.
@ -74,7 +74,7 @@ class btRigidBody : public btCollisionObject
public:
///btRigidBodyConstructionInfo provides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body.
///The btRigidBodyConstructionInfo structure provides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body.
///For dynamic objects, you can use the collision shape to approximate the local inertia tensor, otherwise use the zero vector (default argument)
///You can use the motion state to synchronize the world transform between physics and graphics objects.
///And if the motion state is provided, the rigid body will initialize its initial world transform from the motion state,

View File

@ -97,7 +97,7 @@ int btSimpleDynamicsWorld::stepSimulation( btScalar timeStep,int maxSubSteps, b
void btSimpleDynamicsWorld::clearForces()
{
//todo: iterate over awake simulation islands!
///@todo: iterate over awake simulation islands!
for ( int i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];
@ -210,7 +210,7 @@ void btSimpleDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
void btSimpleDynamicsWorld::synchronizeMotionStates()
{
//todo: iterate over awake simulation islands!
///@todo: iterate over awake simulation islands!
for ( int i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];

View File

@ -22,7 +22,7 @@ class btDispatcher;
class btOverlappingPairCache;
class btConstraintSolver;
///btSimpleDynamicsWorld serves as unit-test and to verify more complicated and optimized dynamics worlds.
///The btSimpleDynamicsWorld serves as unit-test and to verify more complicated and optimized dynamics worlds.
///Please use btDiscreteDynamicsWorld instead (or btContinuousDynamicsWorld once it is finished).
class btSimpleDynamicsWorld : public btDynamicsWorld
{

View File

@ -188,7 +188,7 @@ btScalar btRaycastVehicle::rayCast(btWheelInfo& wheel)
wheel.m_raycastInfo.m_contactNormalWS = rayResults.m_hitNormalInWorld;
wheel.m_raycastInfo.m_isInContact = true;
wheel.m_raycastInfo.m_groundObject = &s_fixedObject;//todo for driving on dynamic/movable objects!;
wheel.m_raycastInfo.m_groundObject = &s_fixedObject;///@todo for driving on dynamic/movable objects!;
//wheel.m_raycastInfo.m_groundObject = object;

View File

@ -32,7 +32,7 @@ subject to the following restrictions:
typedef void (*PosixThreadFunc)(void* userPtr,void* lsMemory);
typedef void* (*PosixlsMemorySetupFunc)();
// PosixThreadSupport helps to initialize/shutdown libspe2, start/stop SPU tasks and communication
///The PosixThreadSupport implements the btThreadSupportInterface using pthreads, to help porting SPU Tasks.
class PosixThreadSupport : public btThreadSupportInterface
{
public:

View File

@ -29,7 +29,8 @@ typedef void* (*SequentiallsMemorySetupFunc)();
///SequentialThreadSupport is a portable non-parallel implementation of the btThreadSupportInterface
///The SequentialThreadSupport is a portable non-parallel implementation of the btThreadSupportInterface
///This is useful for debugging and porting SPU Tasks to other platforms.
class SequentialThreadSupport : public btThreadSupportInterface
{
public:

View File

@ -27,7 +27,7 @@ enum FeatureType { F, E, V };
//----------------------------------------------------------------------------
// Box
//----------------------------------------------------------------------------
///The Box is an internal class used by the boxBoxDistance calculation.
class Box
{
public:
@ -81,6 +81,7 @@ Box::GetAABB(const Matrix3& rotation) const
// BoxPoint
//-------------------------------------------------------------------------------------------------
///The BoxPoint class is an internally used class to contain feature information for boxBoxDistance calculation.
class BoxPoint
{
public:

View File

@ -139,7 +139,7 @@ bool ManifoldResultAddContactPoint(const btVector3& normalOnBInWorld,
newPt.m_combinedRestitution = combinedRestitution;
/*
//potential TODO: SPU callbacks, either immediate (local on the SPU), or deferred
///@todo: SPU callbacks, either immediate (local on the SPU), or deferred
//User can override friction and/or restitution
if (gContactAddedCallback &&
//and if either of the two bodies requires custom material

View File

@ -266,9 +266,6 @@ public:
// spu_printf("processNode with triangleIndex %d\n",triangleIndex);
///TODO: add switch between short int, and int indices, based on indexType
// ugly solution to support both 16bit and 32bit indices
if (m_lsMemPtr->bvhShapeData.gIndexMesh.m_indexType == PHY_SHORT)
{
unsigned short int* indexBasePtr = (unsigned short int*)(m_lsMemPtr->bvhShapeData.gIndexMesh.m_triangleIndexBase+triangleIndex*m_lsMemPtr->bvhShapeData.gIndexMesh.m_triangleIndexStride);
@ -403,7 +400,7 @@ void ProcessConvexConcaveSpuCollision(SpuCollisionPairInput* wuInput, CollisionT
int numBatch = subTrees.size();
for (int i=0;i<numBatch;)
{
// BEN: TODO - can reorder DMA transfers for less stall
//@todo- can reorder DMA transfers for less stall
int remaining = subTrees.size() - i;
int nextBatch = remaining < MAX_SPU_SUBTREE_HEADERS ? remaining : MAX_SPU_SUBTREE_HEADERS;
@ -647,7 +644,7 @@ void handleCollisionPair(SpuCollisionPairInput& collisionPairInput, CollisionTas
cellDmaWaitTagStatusAll(DMA_MASK(1) | DMA_MASK(2));
// Both are compounds, do N^2 CD for now
// TODO: add some AABB-based pruning
///@todo: add some AABB-based pruning (probably not -> slower)
btCompoundShape* spuCompoundShape0 = (btCompoundShape*)collisionShape0Loc;
btCompoundShape* spuCompoundShape1 = (btCompoundShape*)collisionShape1Loc;

View File

@ -720,7 +720,8 @@ static void solveConstraint (SpuSolverConstraint& constraint, SpuSolverBody& bod
//-- CONSTRAINT SETUP METHODS
// Compute the jacobian inverse @@TODO: Optimize
/// Compute the jacobian inverse
///@todo: Optimize
static float computeJacobianInverse (const btRigidBody* rb0, const btRigidBody* rb1,
const btVector3& anchorAinW, const btVector3& anchorBinW, const btVector3& normal)
{

View File

@ -31,6 +31,7 @@ Written by: Marten Svanfeldt
#include <Windows.h>
#endif
///The btSpinlock is a structure to allow multi-platform synchronization. This allows to port the SPU tasks to other platforms.
class btSpinlock
{
public:
@ -67,6 +68,7 @@ private:
//#include <cell/atomic.h>
#include <cell/sync/mutex.h>
///The btSpinlock is a structure to allow multi-platform synchronization. This allows to port the SPU tasks to other platforms.
class btSpinlock
{
public:

View File

@ -26,7 +26,7 @@ subject to the following restrictions:
///The number of threads should be equal to the number of available cores
///Todo: each worker should be linked to a single core, using SetThreadIdealProcessor.
///@todo: each worker should be linked to a single core, using SetThreadIdealProcessor.
///Win32ThreadSupport helps to initialize/shutdown libspe2, start/stop SPU tasks and communication
///Setup and initialize SPU/CELL/Libspe2

View File

@ -44,7 +44,8 @@ struct btSoftBodyWorldInfo
};
/// btSoftBody is work-in-progress
///The btSoftBody is an class to simulate cloth and volumetric soft bodies.
///There is two-way interaction between btSoftBody and btRigidBody/btCollisionObject.
class btSoftBody : public btCollisionObject
{
public:
@ -616,9 +617,10 @@ public:
return m_worldInfo;
}
///@todo: avoid internal softbody shape hack and move collision code to collision library
virtual void setCollisionShape(btCollisionShape* collisionShape)
{
//don't do anything, due to the internal shape hack: todo: fix this
}
bool checkLink( int node0,

View File

@ -125,7 +125,7 @@ struct btSparseSdf
//printf("GC[%d]: %d cells, PpQ: %f\r\n",puid,ncells,nprobes/(btScalar)nqueries);
nqueries=1;
nprobes=1;
++puid; /* TODO: Reset puid's when int range limit is reached */
++puid; ///@todo: Reset puid's when int range limit is reached */
/* else setup a priority list... */
}
//

View File

@ -342,30 +342,30 @@ int shareedge(const int3 &a,const int3 &b)
return 0;
}
class Tri;
class btHullTriangle;
class Tri : public int3
class btHullTriangle : public int3
{
public:
int3 n;
int id;
int vmax;
btScalar rise;
Tri(int a,int b,int c):int3(a,b,c),n(-1,-1,-1)
btHullTriangle(int a,int b,int c):int3(a,b,c),n(-1,-1,-1)
{
vmax=-1;
rise = btScalar(0.0);
}
~Tri()
~btHullTriangle()
{
}
int &neib(int a,int b);
};
int &Tri::neib(int a,int b)
int &btHullTriangle::neib(int a,int b)
{
static int er=-1;
int i;
@ -379,7 +379,7 @@ int &Tri::neib(int a,int b)
btAssert(0);
return er;
}
void HullLibrary::b2bfix(Tri* s,Tri*t)
void HullLibrary::b2bfix(btHullTriangle* s,btHullTriangle*t)
{
int i;
for(i=0;i<3;i++)
@ -395,7 +395,7 @@ void HullLibrary::b2bfix(Tri* s,Tri*t)
}
}
void HullLibrary::removeb2b(Tri* s,Tri*t)
void HullLibrary::removeb2b(btHullTriangle* s,btHullTriangle*t)
{
b2bfix(s,t);
deAllocateTriangle(s);
@ -403,7 +403,7 @@ void HullLibrary::removeb2b(Tri* s,Tri*t)
deAllocateTriangle(t);
}
void HullLibrary::checkit(Tri *t)
void HullLibrary::checkit(btHullTriangle *t)
{
(void)t;
@ -427,36 +427,36 @@ void HullLibrary::checkit(Tri *t)
}
}
Tri* HullLibrary::allocateTriangle(int a,int b,int c)
btHullTriangle* HullLibrary::allocateTriangle(int a,int b,int c)
{
void* mem = btAlignedAlloc(sizeof(Tri),16);
Tri* tr = new (mem)Tri(a,b,c);
void* mem = btAlignedAlloc(sizeof(btHullTriangle),16);
btHullTriangle* tr = new (mem)btHullTriangle(a,b,c);
tr->id = m_tris.size();
m_tris.push_back(tr);
return tr;
}
void HullLibrary::deAllocateTriangle(Tri* tri)
void HullLibrary::deAllocateTriangle(btHullTriangle* tri)
{
btAssert(m_tris[tri->id]==tri);
m_tris[tri->id]=NULL;
tri->~Tri();
tri->~btHullTriangle();
btAlignedFree(tri);
}
void HullLibrary::extrude(Tri *t0,int v)
void HullLibrary::extrude(btHullTriangle *t0,int v)
{
int3 t= *t0;
int n = m_tris.size();
Tri* ta = allocateTriangle(v,t[1],t[2]);
btHullTriangle* ta = allocateTriangle(v,t[1],t[2]);
ta->n = int3(t0->n[0],n+1,n+2);
m_tris[t0->n[0]]->neib(t[1],t[2]) = n+0;
Tri* tb = allocateTriangle(v,t[2],t[0]);
btHullTriangle* tb = allocateTriangle(v,t[2],t[0]);
tb->n = int3(t0->n[1],n+2,n+0);
m_tris[t0->n[1]]->neib(t[2],t[0]) = n+1;
Tri* tc = allocateTriangle(v,t[0],t[1]);
btHullTriangle* tc = allocateTriangle(v,t[0],t[1]);
tc->n = int3(t0->n[2],n+0,n+1);
m_tris[t0->n[2]]->neib(t[0],t[1]) = n+2;
checkit(ta);
@ -469,10 +469,10 @@ void HullLibrary::extrude(Tri *t0,int v)
}
Tri* HullLibrary::extrudable(btScalar epsilon)
btHullTriangle* HullLibrary::extrudable(btScalar epsilon)
{
int i;
Tri *t=NULL;
btHullTriangle *t=NULL;
for(i=0;i<m_tris.size();i++)
{
if(!t || (m_tris[i] && t->rise<m_tris[i]->rise))
@ -550,23 +550,23 @@ int HullLibrary::calchullgen(btVector3 *verts,int verts_count, int vlimit)
btVector3 center = (verts[p[0]]+verts[p[1]]+verts[p[2]]+verts[p[3]]) / btScalar(4.0); // a valid interior point
Tri *t0 = allocateTriangle(p[2],p[3],p[1]); t0->n=int3(2,3,1);
Tri *t1 = allocateTriangle(p[3],p[2],p[0]); t1->n=int3(3,2,0);
Tri *t2 = allocateTriangle(p[0],p[1],p[3]); t2->n=int3(0,1,3);
Tri *t3 = allocateTriangle(p[1],p[0],p[2]); t3->n=int3(1,0,2);
btHullTriangle *t0 = allocateTriangle(p[2],p[3],p[1]); t0->n=int3(2,3,1);
btHullTriangle *t1 = allocateTriangle(p[3],p[2],p[0]); t1->n=int3(3,2,0);
btHullTriangle *t2 = allocateTriangle(p[0],p[1],p[3]); t2->n=int3(0,1,3);
btHullTriangle *t3 = allocateTriangle(p[1],p[0],p[2]); t3->n=int3(1,0,2);
isextreme[p[0]]=isextreme[p[1]]=isextreme[p[2]]=isextreme[p[3]]=1;
checkit(t0);checkit(t1);checkit(t2);checkit(t3);
for(j=0;j<m_tris.size();j++)
{
Tri *t=m_tris[j];
btHullTriangle *t=m_tris[j];
btAssert(t);
btAssert(t->vmax<0);
btVector3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]);
t->vmax = maxdirsterid(verts,verts_count,n,allow);
t->rise = dot(n,verts[t->vmax]-verts[(*t)[0]]);
}
Tri *te;
btHullTriangle *te;
vlimit-=4;
while(vlimit >0 && ((te=extrudable(epsilon)) != 0))
{
@ -594,7 +594,7 @@ int HullLibrary::calchullgen(btVector3 *verts,int verts_count, int vlimit)
int3 nt=*m_tris[j];
if(above(verts,nt,center,btScalar(0.01)*epsilon) || cross(verts[nt[1]]-verts[nt[0]],verts[nt[2]]-verts[nt[1]]).length()< epsilon*epsilon*btScalar(0.1) )
{
Tri *nb = m_tris[m_tris[j]->n[0]];
btHullTriangle *nb = m_tris[m_tris[j]->n[0]];
btAssert(nb);btAssert(!hasvert(*nb,v));btAssert(nb->id<j);
extrude(nb,v);
j=m_tris.size();
@ -603,7 +603,7 @@ int HullLibrary::calchullgen(btVector3 *verts,int verts_count, int vlimit)
j=m_tris.size();
while(j--)
{
Tri *t=m_tris[j];
btHullTriangle *t=m_tris[j];
if(!t) continue;
if(t->vmax>=0) break;
btVector3 n=TriNormal(verts[(*t)[0]],verts[(*t)[1]],verts[(*t)[2]]);

View File

@ -188,7 +188,7 @@ public:
class HullLibrary
{
btAlignedObjectArray<class Tri*> m_tris;
btAlignedObjectArray<class btHullTriangle*> m_tris;
public:
@ -203,15 +203,15 @@ private:
bool ComputeHull(unsigned int vcount,const btVector3 *vertices,PHullResult &result,unsigned int vlimit);
class Tri* allocateTriangle(int a,int b,int c);
void deAllocateTriangle(Tri*);
void b2bfix(Tri* s,Tri*t);
class btHullTriangle* allocateTriangle(int a,int b,int c);
void deAllocateTriangle(btHullTriangle*);
void b2bfix(btHullTriangle* s,btHullTriangle*t);
void removeb2b(Tri* s,Tri*t);
void removeb2b(btHullTriangle* s,btHullTriangle*t);
void checkit(Tri *t);
void checkit(btHullTriangle *t);
Tri* extrudable(btScalar epsilon);
btHullTriangle* extrudable(btScalar epsilon);
int calchull(btVector3 *verts,int verts_count, TUIntArray& tris_out, int &tris_count,int vlimit);
@ -221,7 +221,7 @@ private:
class ConvexH* ConvexHCrop(ConvexH& convex,const btPlane& slice);
void extrude(class Tri* t0,int v);
void extrude(class btHullTriangle* t0,int v);
ConvexH* test_cube();

View File

@ -47,7 +47,7 @@ public:
};
/** @brief btQuadWord is base-class for vectors, points */
/** @brief The btQuadWord is base-class for vectors, points */
class btQuadWord : public btQuadWordStorage
{
public:

View File

@ -23,6 +23,7 @@ Nov.2006
#include "btScalar.h" //for btAssert
#include "btAlignedAllocator.h"
///The btBlock class is an internal structure for the btStackAlloc memory allocator.
struct btBlock
{
btBlock* previous;