Fixed warnings in Bullet/src core library

Thanks Martijn Reuvers from Two Tribes B.V. (www.twotribes.com) for the patch

To make this work more visible, suppress warnings in external libraries in Extras (COLLADA_DOM, libxml and glui contain many warnings)
Added PreprocessorDefinitions: _CRT_SECURE_NO_DEPRECATE;_CRT_NONSTDC_NO_DEPRECATE to vcproj files
This commit is contained in:
erwin.coumans
2008-05-10 18:00:21 +00:00
parent 739d09a7af
commit bd97c5e569
285 changed files with 11554 additions and 11205 deletions

View File

@@ -47,7 +47,7 @@ public:
BP_FP_INT_TYPE m_pos; // low bit is min/max
BP_FP_INT_TYPE m_handle;
BP_FP_INT_TYPE IsMax() const {return m_pos & 1;}
BP_FP_INT_TYPE IsMax() const {return static_cast<BP_FP_INT_TYPE>(m_pos & 1);}
};
public:
@@ -223,14 +223,14 @@ template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::destroyProxy(btBroadphaseProxy* proxy,btDispatcher* dispatcher)
{
Handle* handle = static_cast<Handle*>(proxy);
removeHandle(handle->m_uniqueId,dispatcher);
removeHandle(static_cast<BP_FP_INT_TYPE>(handle->m_uniqueId), dispatcher);
}
template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::setAabb(btBroadphaseProxy* proxy,const btVector3& aabbMin,const btVector3& aabbMax,btDispatcher* dispatcher)
{
Handle* handle = static_cast<Handle*>(proxy);
updateHandle(handle->m_uniqueId,aabbMin,aabbMax,dispatcher);
updateHandle(static_cast<BP_FP_INT_TYPE>(handle->m_uniqueId), aabbMin, aabbMax,dispatcher);
}
@@ -247,7 +247,7 @@ m_userPairCallback(0),
m_ownsPairCache(false),
m_invalidPair(0)
{
BP_FP_INT_TYPE maxHandles = userMaxHandles+1;//need to add one sentinel handle
BP_FP_INT_TYPE maxHandles = static_cast<BP_FP_INT_TYPE>(userMaxHandles+1);//need to add one sentinel handle
if (!m_pairCache)
{
@@ -278,7 +278,7 @@ m_invalidPair(0)
m_firstFreeHandle = 1;
{
for (BP_FP_INT_TYPE i = m_firstFreeHandle; i < maxHandles; i++)
m_pHandles[i].SetNextFree(i + 1);
m_pHandles[i].SetNextFree(static_cast<BP_FP_INT_TYPE>(i + 1));
m_pHandles[maxHandles - 1].SetNextFree(0);
}
@@ -386,7 +386,7 @@ BP_FP_INT_TYPE btAxisSweep3Internal<BP_FP_INT_TYPE>::addHandle(const btPoint3& a
Handle* pHandle = getHandle(handle);
pHandle->m_uniqueId = handle;
pHandle->m_uniqueId = static_cast<int>(handle);
//pHandle->m_pOverlaps = 0;
pHandle->m_clientObject = pOwner;
pHandle->m_collisionFilterGroup = collisionFilterGroup;
@@ -394,7 +394,7 @@ BP_FP_INT_TYPE btAxisSweep3Internal<BP_FP_INT_TYPE>::addHandle(const btPoint3& a
pHandle->m_multiSapParentProxy = multiSapProxy;
// compute current limit of edge arrays
BP_FP_INT_TYPE limit = m_numHandles * 2;
BP_FP_INT_TYPE limit = static_cast<BP_FP_INT_TYPE>(m_numHandles * 2);
// insert new edges just inside the max boundary edge
@@ -411,7 +411,7 @@ BP_FP_INT_TYPE btAxisSweep3Internal<BP_FP_INT_TYPE>::addHandle(const btPoint3& a
m_pEdges[axis][limit].m_pos = max[axis];
m_pEdges[axis][limit].m_handle = handle;
pHandle->m_minEdges[axis] = limit - 1;
pHandle->m_minEdges[axis] = static_cast<BP_FP_INT_TYPE>(limit - 1);
pHandle->m_maxEdges[axis] = limit;
}
@@ -443,7 +443,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::removeHandle(BP_FP_INT_TYPE handle,bt
}
// compute current limit of edge arrays
int limit = m_numHandles * 2;
int limit = static_cast<int>(m_numHandles * 2);
int axis;
@@ -680,7 +680,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::updateHandle(BP_FP_INT_TYPE handle, c
// sorting a min edge downwards can only ever *add* overlaps
template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::sortMinDown(int axis, BP_FP_INT_TYPE edge, btDispatcher* dispatcher, bool updateOverlaps)
void btAxisSweep3Internal<BP_FP_INT_TYPE>::sortMinDown(int axis, BP_FP_INT_TYPE edge, btDispatcher* /* dispatcher */, bool updateOverlaps)
{
Edge* pEdge = m_pEdges[axis] + edge;
@@ -834,7 +834,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::sortMaxDown(int axis, BP_FP_INT_TYPE
// sorting a max edge upwards can only ever *add* overlaps
template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::sortMaxUp(int axis, BP_FP_INT_TYPE edge, btDispatcher* dispatcher, bool updateOverlaps)
void btAxisSweep3Internal<BP_FP_INT_TYPE>::sortMaxUp(int axis, BP_FP_INT_TYPE edge, btDispatcher* /* dispatcher */, bool updateOverlaps)
{
Edge* pEdge = m_pEdges[axis] + edge;
Edge* pNext = pEdge + 1;

View File

@@ -64,7 +64,6 @@ CONCAVE_SHAPES_END_HERE,
MAX_BROADPHASE_COLLISION_TYPES
};
//#include <stdio.h>
///btBroadphaseProxy
ATTRIBUTE_ALIGNED16(struct) btBroadphaseProxy

View File

@@ -279,7 +279,7 @@ static btDbvt::Node* topdown(btDbvt* pdbvt,
{
if((splitcount[i][0]>0)&&(splitcount[i][1]>0))
{
const int midp=btFabs(splitcount[i][0]-splitcount[i][1]);
const int midp=static_cast<int>(btFabs(static_cast<btScalar>(splitcount[i][0]-splitcount[i][1])));
if(midp<bestmidp)
{
bestaxis=i;

View File

@@ -95,7 +95,7 @@ struct btDbvt
// Constants
enum {
TREETREE_STACKSIZE = 128,
VOLUMETREE_STACKSIZE = 64,
VOLUMETREE_STACKSIZE = 64
};
// Fields

View File

@@ -50,7 +50,7 @@ struct ProfileScope
//
static inline int hash(unsigned int i,unsigned int j)
{
int key=((unsigned int)i)|(((unsigned int)j)<<16);
int key=static_cast<int>(((unsigned int)i)|(((unsigned int)j)<<16));
key+=~(key<<15);
key^= (key>>10);
key+= (key<<3);
@@ -104,7 +104,7 @@ struct btDbvtBroadphaseCollider : btDbvt::ICollide
int pid;
btDbvtBroadphaseCollider(btDbvtBroadphase* p,int id) : pbp(p),pid(id) {}
virtual void Process(const btDbvt::Node* na)
virtual void Process(const btDbvt::Node* /*na*/)
{
}
virtual bool Descent(const btDbvt::Node*)
@@ -163,12 +163,12 @@ btDbvtBroadphase::~btDbvtBroadphase()
//
btBroadphaseProxy* btDbvtBroadphase::createProxy( const btVector3& aabbMin,
const btVector3& aabbMax,
int shapeType,
int /*shapeType*/,
void* userPtr,
short int collisionFilterGroup,
short int collisionFilterMask,
btDispatcher* dispatcher,
void* multiSapProxy)
btDispatcher* /*dispatcher*/,
void* /*multiSapProxy*/)
{
btDbvtProxy* proxy=new btDbvtProxy(userPtr,collisionFilterGroup,collisionFilterMask);
proxy->aabb = btDbvtAabbMm::FromMM(aabbMin,aabbMax);
@@ -197,7 +197,7 @@ void btDbvtBroadphase::destroyProxy( btBroadphaseProxy* absproxy,
void btDbvtBroadphase::setAabb( btBroadphaseProxy* absproxy,
const btVector3& aabbMin,
const btVector3& aabbMax,
btDispatcher* dispatcher)
btDispatcher* /*dispatcher*/)
{
btDbvtProxy* proxy=(btDbvtProxy*)absproxy;
btDbvtAabbMm aabb=btDbvtAabbMm::FromMM(aabbMin,aabbMax);

View File

@@ -68,7 +68,7 @@ struct btDbvtBroadphase : btBroadphaseInterface
DYNAMIC_SET = 0, /* Dynamic set index */
FIXED_SET = 1, /* Fixed set index */
STAGECOUNT = 2, /* Number of stages */
PREDICTED_FRAMES = 2, /* Frames prediction */
PREDICTED_FRAMES = 2 /* Frames prediction */
};
/* Fields */
btDbvt m_sets[2]; // Dbvt sets

View File

@@ -37,7 +37,7 @@ public:
*/
btMultiSapBroadphase::btMultiSapBroadphase(int maxProxies,btOverlappingPairCache* pairCache)
btMultiSapBroadphase::btMultiSapBroadphase(int /*maxProxies*/,btOverlappingPairCache* pairCache)
:m_overlappingPairs(pairCache),
m_ownsPairCache(false),
m_invalidPair(0),
@@ -104,7 +104,7 @@ void btMultiSapBroadphase::buildTree(const btVector3& bvhAabbMin,const btVector3
m_optimizedAabbTree->buildInternal();
}
btBroadphaseProxy* btMultiSapBroadphase::createProxy( const btVector3& aabbMin, const btVector3& aabbMax,int shapeType,void* userPtr, short int collisionFilterGroup,short int collisionFilterMask, btDispatcher* dispatcher,void* ignoreMe)
btBroadphaseProxy* btMultiSapBroadphase::createProxy( const btVector3& aabbMin, const btVector3& aabbMax,int shapeType,void* userPtr, short int collisionFilterGroup,short int collisionFilterMask, btDispatcher* dispatcher,void* /*ignoreMe*/)
{
//void* ignoreMe -> we could think of recursive multi-sap, if someone is interested
@@ -117,7 +117,7 @@ btBroadphaseProxy* btMultiSapBroadphase::createProxy( const btVector3& aabbMin,
return proxy;
}
void btMultiSapBroadphase::destroyProxy(btBroadphaseProxy* proxy,btDispatcher* dispatcher)
void btMultiSapBroadphase::destroyProxy(btBroadphaseProxy* /*proxy*/,btDispatcher* /*dispatcher*/)
{
///not yet
btAssert(0);
@@ -128,13 +128,14 @@ void btMultiSapBroadphase::destroyProxy(btBroadphaseProxy* proxy,btDispatcher* d
void btMultiSapBroadphase::addToChildBroadphase(btMultiSapProxy* parentMultiSapProxy, btBroadphaseProxy* childProxy, btBroadphaseInterface* childBroadphase)
{
void* mem = btAlignedAlloc(sizeof(btBridgeProxy),16);
btBridgeProxy* bridgeProxyRef = new(mem) btBridgeProxy();
btBridgeProxy* bridgeProxyRef = new(mem) btBridgeProxy;
bridgeProxyRef->m_childProxy = childProxy;
bridgeProxyRef->m_childBroadphase = childBroadphase;
parentMultiSapProxy->m_bridgeProxies.push_back(bridgeProxyRef);
}
bool boxIsContainedWithinBox(const btVector3& amin,const btVector3& amax,const btVector3& bmin,const btVector3& bmax);
bool boxIsContainedWithinBox(const btVector3& amin,const btVector3& amax,const btVector3& bmin,const btVector3& bmax)
{
return
@@ -157,8 +158,8 @@ void btMultiSapBroadphase::setAabb(btBroadphaseProxy* proxy,const btVector3& aab
multiProxy->m_aabbMax = aabbMax;
bool fullyContained = false;
bool alreadyInSimple = false;
// bool fullyContained = false;
// bool alreadyInSimple = false;
@@ -177,7 +178,7 @@ void btMultiSapBroadphase::setAabb(btBroadphaseProxy* proxy,const btVector3& aab
}
virtual void processNode(int nodeSubPart, int broadphaseIndex)
virtual void processNode(int /*nodeSubPart*/, int broadphaseIndex)
{
btBroadphaseInterface* childBroadphase = m_multiSap->getBroadphaseArray()[broadphaseIndex];

View File

@@ -142,7 +142,7 @@ btBroadphasePair* btHashedOverlappingPairCache::findPair(btBroadphaseProxy* prox
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hash = getHash(proxyId1, proxyId2) & (m_overlappingPairArray.capacity()-1);
int hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1), static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1));
if (hash >= m_hashTable.size())
{
@@ -200,7 +200,7 @@ void btHashedOverlappingPairCache::growTables()
int proxyId2 = pair.m_pProxy1->getUid();
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hashValue = getHash(proxyId1,proxyId2) & (m_overlappingPairArray.capacity()-1); // New hash value with new mask
int hashValue = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1),static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1)); // New hash value with new mask
m_next[i] = m_hashTable[hashValue];
m_hashTable[hashValue] = i;
}
@@ -218,9 +218,8 @@ btBroadphasePair* btHashedOverlappingPairCache::internalAddPair(btBroadphaseProx
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hash = getHash(proxyId1, proxyId2) & (m_overlappingPairArray.capacity()-1);
int hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1),static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1)); // New hash value with new mask
btBroadphasePair* pair = internalFindPair(proxy0, proxy1, hash);
if (pair != NULL)
@@ -245,7 +244,7 @@ btBroadphasePair* btHashedOverlappingPairCache::internalAddPair(btBroadphaseProx
{
growTables();
//hash with new capacity
hash = getHash(proxyId1, proxyId2) & (m_overlappingPairArray.capacity()-1);
hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1),static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1));
}
pair = new (mem) btBroadphasePair(*proxy0,*proxy1);
@@ -273,7 +272,7 @@ void* btHashedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* pro
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hash = getHash(proxyId1, proxyId2) & (m_overlappingPairArray.capacity()-1);
int hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1),static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1));
btBroadphasePair* pair = internalFindPair(proxy0, proxy1, hash);
if (pair == NULL)
@@ -328,7 +327,7 @@ void* btHashedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* pro
// Remove the last pair from the hash table.
const btBroadphasePair* last = &m_overlappingPairArray[lastPairIndex];
/* missing swap here too, Nat. */
int lastHash = getHash(last->m_pProxy0->getUid(), last->m_pProxy1->getUid()) & (m_overlappingPairArray.capacity()-1);
int lastHash = static_cast<int>(getHash(static_cast<unsigned int>(last->m_pProxy0->getUid()), static_cast<unsigned int>(last->m_pProxy1->getUid())) & (m_overlappingPairArray.capacity()-1));
index = m_hashTable[lastHash];
btAssert(index != BT_NULL_PAIR);

View File

@@ -205,7 +205,7 @@ private:
SIMD_FORCE_INLINE unsigned int getHash(unsigned int proxyId1, unsigned int proxyId2)
{
int key = ((unsigned int)proxyId1) | (((unsigned int)proxyId2) <<16);
int key = static_cast<int>(((unsigned int)proxyId1) | (((unsigned int)proxyId2) <<16));
// Thomas Wang's hash
key += ~(key << 15);
@@ -214,7 +214,7 @@ private:
key ^= (key >> 6);
key += ~(key << 11);
key ^= (key >> 16);
return key;
return static_cast<unsigned int>(key);
}
@@ -380,7 +380,7 @@ public:
return m_overlappingPairArray;
}
virtual void cleanOverlappingPair(btBroadphasePair& pair,btDispatcher* dispatcher)
virtual void cleanOverlappingPair(btBroadphasePair& /*pair*/,btDispatcher* /*dispatcher*/)
{
}
@@ -390,20 +390,20 @@ public:
return 0;
}
virtual void cleanProxyFromPairs(btBroadphaseProxy* proxy,btDispatcher* dispatcher)
virtual void cleanProxyFromPairs(btBroadphaseProxy* /*proxy*/,btDispatcher* /*dispatcher*/)
{
}
virtual void setOverlapFilterCallback(btOverlapFilterCallback* callback)
virtual void setOverlapFilterCallback(btOverlapFilterCallback* /*callback*/)
{
}
virtual void processAllOverlappingPairs(btOverlapCallback*,btDispatcher* dispatcher)
virtual void processAllOverlappingPairs(btOverlapCallback*,btDispatcher* /*dispatcher*/)
{
}
virtual btBroadphasePair* findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1)
virtual btBroadphasePair* findPair(btBroadphaseProxy* /*proxy0*/, btBroadphaseProxy* /*proxy1*/)
{
return 0;
}
@@ -413,17 +413,17 @@ public:
return true;
}
virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1)
virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* /*proxy0*/,btBroadphaseProxy* /*proxy1*/)
{
return 0;
}
virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1,btDispatcher* dispatcher)
virtual void* removeOverlappingPair(btBroadphaseProxy* /*proxy0*/,btBroadphaseProxy* /*proxy1*/,btDispatcher* /*dispatcher*/)
{
return 0;
}
virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy0,btDispatcher* dispatcher)
virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* /*proxy0*/,btDispatcher* /*dispatcher*/)
{
}
@@ -434,4 +434,3 @@ public:
#endif //OVERLAPPING_PAIR_CACHE_H

View File

@@ -83,7 +83,7 @@ btSimpleBroadphase::~btSimpleBroadphase()
}
btBroadphaseProxy* btSimpleBroadphase::createProxy( const btVector3& aabbMin, const btVector3& aabbMax,int shapeType,void* userPtr ,short int collisionFilterGroup,short int collisionFilterMask, btDispatcher* dispatcher,void* multiSapProxy)
btBroadphaseProxy* btSimpleBroadphase::createProxy( const btVector3& aabbMin, const btVector3& aabbMax,int shapeType,void* userPtr ,short int collisionFilterGroup,short int collisionFilterMask, btDispatcher* /*dispatcher*/,void* multiSapProxy)
{
if (m_numHandles >= m_maxHandles)
{
@@ -139,7 +139,7 @@ void btSimpleBroadphase::destroyProxy(btBroadphaseProxy* proxyOrg,btDispatcher*
}
void btSimpleBroadphase::setAabb(btBroadphaseProxy* proxy,const btVector3& aabbMin,const btVector3& aabbMax, btDispatcher* dispatcher)
void btSimpleBroadphase::setAabb(btBroadphaseProxy* proxy,const btVector3& aabbMin,const btVector3& aabbMax, btDispatcher* /*dispatcher*/)
{
btSimpleBroadphaseProxy* sbp = getSimpleProxyFromProxy(proxy);
sbp->m_min = aabbMin;

View File

@@ -53,6 +53,8 @@ void SphereTriangleDetector::getClosestPoints(const ClosestPointInput& input,Res
// See also geometrictools.com
// Basic idea: D = |p - (lo + t0*lv)| where t0 = lv . (p - lo) / lv . lv
btScalar SegmentSqrDistance(const btVector3& from, const btVector3& to,const btVector3 &p, btVector3 &nearest);
btScalar SegmentSqrDistance(const btVector3& from, const btVector3& to,const btVector3 &p, btVector3 &nearest) {
btVector3 diff = p - from;
btVector3 v = to - from;

View File

@@ -78,7 +78,7 @@ void btBoxBoxCollisionAlgorithm::processCollision (btCollisionObject* body0,btCo
}
btScalar btBoxBoxCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
btScalar btBoxBoxCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/,btCollisionObject* /*body1*/,const btDispatcherInfo& /*dispatchInfo*/,btManifoldResult* /*resultOut*/)
{
//not yet
return 1.f;

View File

@@ -63,23 +63,27 @@ static btScalar dDOT44 (const btScalar *a, const btScalar *b) { return dDOTpq(a,
static btScalar dDOT41 (const btScalar *a, const btScalar *b) { return dDOTpq(a,b,4,1); }
static btScalar dDOT14 (const btScalar *a, const btScalar *b) { return dDOTpq(a,b,1,4); }
#define dMULTIPLYOP1_331(A,op,B,C) \
do { \
{\
(A)[0] op dDOT41((B),(C)); \
(A)[1] op dDOT41((B+1),(C)); \
(A)[2] op dDOT41((B+2),(C)); \
} while(0)
}
#define dMULTIPLYOP0_331(A,op,B,C) \
do { \
{ \
(A)[0] op dDOT((B),(C)); \
(A)[1] op dDOT((B+4),(C)); \
(A)[2] op dDOT((B+8),(C)); \
} while(0)
}
#define dMULTIPLY1_331(A,B,C) dMULTIPLYOP1_331(A,=,B,C)
#define dMULTIPLY0_331(A,B,C) dMULTIPLYOP0_331(A,=,B,C)
typedef btScalar dMatrix3[4*3];
void dLineClosestApproach (const btVector3& pa, const btVector3& ua,
const btVector3& pb, const btVector3& ub,
btScalar *alpha, btScalar *beta);
void dLineClosestApproach (const btVector3& pa, const btVector3& ua,
const btVector3& pb, const btVector3& ub,
btScalar *alpha, btScalar *beta)
@@ -118,7 +122,7 @@ static int intersectRectQuad2 (btScalar h[2], btScalar p[8], btScalar ret[16])
{
// q (and r) contain nq (and nr) coordinate points for the current (and
// chopped) polygons
int nq=4,nr;
int nq=4,nr=0;
btScalar buffer[16];
btScalar *q = p;
btScalar *r = ret;
@@ -178,6 +182,7 @@ static int intersectRectQuad2 (btScalar h[2], btScalar p[8], btScalar ret[16])
// n must be in the range [1..8]. m must be in the range [1..n]. i0 must be
// in the range [0..n-1].
void cullPoints2 (int n, btScalar p[], int m, int i0, int iret[]);
void cullPoints2 (int n, btScalar p[], int m, int i0, int iret[])
{
// compute the centroid of the polygon in cx,cy
@@ -244,12 +249,16 @@ void cullPoints2 (int n, btScalar p[], int m, int i0, int iret[])
int dBoxBox2 (const btVector3& p1, const dMatrix3 R1,
const btVector3& side1, const btVector3& p2,
const dMatrix3 R2, const btVector3& side2,
btVector3& normal, btScalar *depth, int *return_code,
int maxc, dContactGeom *contact, int skip,btDiscreteCollisionDetectorInterface::Result& output)
int maxc, dContactGeom * /*contact*/, int /*skip*/,btDiscreteCollisionDetectorInterface::Result& output);
int dBoxBox2 (const btVector3& p1, const dMatrix3 R1,
const btVector3& side1, const btVector3& p2,
const dMatrix3 R2, const btVector3& side2,
btVector3& normal, btScalar *depth, int *return_code,
int maxc, dContactGeom * /*contact*/, int /*skip*/,btDiscreteCollisionDetectorInterface::Result& output)
{
const btScalar fudge_factor = btScalar(1.05);
btVector3 p,pp,normalC;
@@ -626,7 +635,7 @@ int dBoxBox2 (const btVector3& p1, const dMatrix3 R1,
return cnum;
}
void btBoxBoxDetector::getClosestPoints(const ClosestPointInput& input,Result& output,class btIDebugDraw* debugDraw)
void btBoxBoxDetector::getClosestPoints(const ClosestPointInput& input,Result& output,class btIDebugDraw* /*debugDraw*/)
{
const btTransform& transformA = input.m_transformA;

View File

@@ -280,7 +280,7 @@ void* btCollisionDispatcher::allocateCollisionAlgorithm(int size)
}
//warn user for overflow?
return btAlignedAlloc(size,16);
return btAlignedAlloc(static_cast<std::size_t>(size), 16);
}
void btCollisionDispatcher::freeCollisionAlgorithm(void* ptr)

View File

@@ -84,7 +84,7 @@ protected:
char m_pad[7];
virtual bool checkCollideWithOverride(btCollisionObject* co)
virtual bool checkCollideWithOverride(btCollisionObject* /* co */)
{
return true;
}

View File

@@ -1,3 +1,17 @@
/*
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.
*/
#include "LinearMath/btScalar.h"
@@ -25,7 +39,7 @@ void btSimulationIslandManager::initUnionFind(int n)
}
void btSimulationIslandManager::findUnions(btDispatcher* dispatcher,btCollisionWorld* colWorld)
void btSimulationIslandManager::findUnions(btDispatcher* /* dispatcher */,btCollisionWorld* colWorld)
{
{

View File

@@ -32,9 +32,9 @@ class btSimulationIslandManager
{
btUnionFind m_unionFind;
btAlignedObjectArray<btPersistentManifold*> m_islandmanifold;
btAlignedObjectArray<btCollisionObject* > m_islandBodies;
btAlignedObjectArray<btPersistentManifold*> m_islandmanifold;
btAlignedObjectArray<btCollisionObject* > m_islandBodies;
public:
btSimulationIslandManager();

View File

@@ -21,7 +21,12 @@ subject to the following restrictions:
can be used by probes that are checking whether the
library is actually installed.
*/
extern "C" void btBulletCollisionProbe () {}
extern "C"
{
void btBulletCollisionProbe ();
void btBulletCollisionProbe () {}
}

View File

@@ -26,6 +26,7 @@ subject to the following restrictions:
class btOptimizedBvh;
ATTRIBUTE_ALIGNED16(struct) btCompoundShapeChild
{
BT_DECLARE_ALIGNED_ALLOCATOR();

View File

@@ -182,7 +182,7 @@ void btHeightfieldTerrainShape::getVertex(int x,int y,btVector3& vertex) const
}
void btHeightfieldTerrainShape::quantizeWithClamp(int* out, const btVector3& point,int isMax) const
void btHeightfieldTerrainShape::quantizeWithClamp(int* out, const btVector3& point,int /*isMax*/) const
{
btVector3 clampedPoint(point);
clampedPoint.setMax(m_localAabbMin);

View File

@@ -301,14 +301,14 @@ void btOptimizedBvh::updateBvhNodes(btStridingMeshInterface* meshInterface,int f
int curNodeSubPart=-1;
//get access info to trianglemesh data
const unsigned char *vertexbase;
int numverts;
PHY_ScalarType type;
int stride;
const unsigned char *indexbase;
int indexstride;
int numfaces;
PHY_ScalarType indicestype;
const unsigned char *vertexbase = 0;
int numverts = 0;
PHY_ScalarType type = PHY_INTEGER;
int stride = 0;
const unsigned char *indexbase = 0;
int indexstride = 0;
int numfaces = 0;
PHY_ScalarType indicestype = PHY_INTEGER;
btVector3 triangleVerts[3];
btVector3 aabbMin,aabbMax;
@@ -532,11 +532,11 @@ void btOptimizedBvh::updateSubtreeHeaders(int leftChildNodexIndex,int rightChild
btQuantizedBvhNode& leftChildNode = m_quantizedContiguousNodes[leftChildNodexIndex];
int leftSubTreeSize = leftChildNode.isLeafNode() ? 1 : leftChildNode.getEscapeIndex();
int leftSubTreeSizeInBytes = leftSubTreeSize * sizeof(btQuantizedBvhNode);
int leftSubTreeSizeInBytes = leftSubTreeSize * static_cast<int>(sizeof(btQuantizedBvhNode));
btQuantizedBvhNode& rightChildNode = m_quantizedContiguousNodes[rightChildNodexIndex];
int rightSubTreeSize = rightChildNode.isLeafNode() ? 1 : rightChildNode.getEscapeIndex();
int rightSubTreeSizeInBytes = rightSubTreeSize * sizeof(btQuantizedBvhNode);
int rightSubTreeSizeInBytes = rightSubTreeSize * static_cast<int>(sizeof(btQuantizedBvhNode));
if(leftSubTreeSizeInBytes <= MAX_SUBTREE_SIZE_IN_BYTES)
{
@@ -606,6 +606,7 @@ int btOptimizedBvh::sortAndCalcSplittingIndex(int startIndex,int endIndex,int sp
}
bool unbal = (splitIndex==startIndex) || (splitIndex == (endIndex));
(void)unbal;
btAssert(!unbal);
return splitIndex;
@@ -785,6 +786,7 @@ void btOptimizedBvh::walkStacklessQuantizedTreeAgainstRay(btNodeOverlapCallback*
int curIndex = startNodeIndex;
int walkIterations = 0;
int subTreeSize = endNodeIndex - startNodeIndex;
(void)subTreeSize;
const btQuantizedBvhNode* rootNode = &m_quantizedContiguousNodes[startNodeIndex];
int escapeIndex;
@@ -909,6 +911,7 @@ void btOptimizedBvh::walkStacklessQuantizedTree(btNodeOverlapCallback* nodeCallb
int curIndex = startNodeIndex;
int walkIterations = 0;
int subTreeSize = endNodeIndex - startNodeIndex;
(void)subTreeSize;
const btQuantizedBvhNode* rootNode = &m_quantizedContiguousNodes[startNodeIndex];
int escapeIndex;
@@ -1080,7 +1083,7 @@ unsigned btOptimizedBvh::calculateSerializeBufferSize()
return baseSize + m_curNodeIndex * sizeof(btOptimizedBvhNode);
}
bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferSize, bool i_swapEndian)
bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned /*i_dataBufferSize */, bool i_swapEndian)
{
assert(m_subtreeHeaderCount == m_SubtreeHeaders.size());
m_subtreeHeaderCount = m_SubtreeHeaders.size();
@@ -1101,7 +1104,7 @@ bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferS
if (i_swapEndian)
{
targetBvh->m_curNodeIndex = btSwapEndian(m_curNodeIndex);
targetBvh->m_curNodeIndex = static_cast<int>(btSwapEndian(m_curNodeIndex));
btSwapVector3Endian(m_bvhAabbMin,targetBvh->m_bvhAabbMin);
@@ -1109,7 +1112,7 @@ bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferS
btSwapVector3Endian(m_bvhQuantization,targetBvh->m_bvhQuantization);
targetBvh->m_traversalMode = (btTraversalMode)btSwapEndian(m_traversalMode);
targetBvh->m_subtreeHeaderCount = btSwapEndian(m_subtreeHeaderCount);
targetBvh->m_subtreeHeaderCount = static_cast<int>(btSwapEndian(m_subtreeHeaderCount));
}
else
{
@@ -1147,7 +1150,7 @@ bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferS
targetBvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[1] = btSwapEndian(m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[1]);
targetBvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[2] = btSwapEndian(m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[2]);
targetBvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex = btSwapEndian(m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex);
targetBvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex = static_cast<int>(btSwapEndian(m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex));
}
}
else
@@ -1181,9 +1184,9 @@ bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferS
btSwapVector3Endian(m_contiguousNodes[nodeIndex].m_aabbMinOrg, targetBvh->m_contiguousNodes[nodeIndex].m_aabbMinOrg);
btSwapVector3Endian(m_contiguousNodes[nodeIndex].m_aabbMaxOrg, targetBvh->m_contiguousNodes[nodeIndex].m_aabbMaxOrg);
targetBvh->m_contiguousNodes[nodeIndex].m_escapeIndex = btSwapEndian(m_contiguousNodes[nodeIndex].m_escapeIndex);
targetBvh->m_contiguousNodes[nodeIndex].m_subPart = btSwapEndian(m_contiguousNodes[nodeIndex].m_subPart);
targetBvh->m_contiguousNodes[nodeIndex].m_triangleIndex = btSwapEndian(m_contiguousNodes[nodeIndex].m_triangleIndex);
targetBvh->m_contiguousNodes[nodeIndex].m_escapeIndex = static_cast<int>(btSwapEndian(m_contiguousNodes[nodeIndex].m_escapeIndex));
targetBvh->m_contiguousNodes[nodeIndex].m_subPart = static_cast<int>(btSwapEndian(m_contiguousNodes[nodeIndex].m_subPart));
targetBvh->m_contiguousNodes[nodeIndex].m_triangleIndex = static_cast<int>(btSwapEndian(m_contiguousNodes[nodeIndex].m_triangleIndex));
}
}
else
@@ -1218,8 +1221,8 @@ bool btOptimizedBvh::serialize(void *o_alignedDataBuffer, unsigned i_dataBufferS
targetBvh->m_SubtreeHeaders[i].m_quantizedAabbMax[1] = btSwapEndian(m_SubtreeHeaders[i].m_quantizedAabbMax[1]);
targetBvh->m_SubtreeHeaders[i].m_quantizedAabbMax[2] = btSwapEndian(m_SubtreeHeaders[i].m_quantizedAabbMax[2]);
targetBvh->m_SubtreeHeaders[i].m_rootNodeIndex = btSwapEndian(m_SubtreeHeaders[i].m_rootNodeIndex);
targetBvh->m_SubtreeHeaders[i].m_subtreeSize = btSwapEndian(m_SubtreeHeaders[i].m_subtreeSize);
targetBvh->m_SubtreeHeaders[i].m_rootNodeIndex = static_cast<int>(btSwapEndian(m_SubtreeHeaders[i].m_rootNodeIndex));
targetBvh->m_SubtreeHeaders[i].m_subtreeSize = static_cast<int>(btSwapEndian(m_SubtreeHeaders[i].m_subtreeSize));
}
}
else
@@ -1256,14 +1259,14 @@ btOptimizedBvh *btOptimizedBvh::deSerializeInPlace(void *i_alignedDataBuffer, un
if (i_swapEndian)
{
bvh->m_curNodeIndex = btSwapEndian(bvh->m_curNodeIndex);
bvh->m_curNodeIndex = static_cast<int>(btSwapEndian(bvh->m_curNodeIndex));
btUnSwapVector3Endian(bvh->m_bvhAabbMin);
btUnSwapVector3Endian(bvh->m_bvhAabbMax);
btUnSwapVector3Endian(bvh->m_bvhQuantization);
bvh->m_traversalMode = (btTraversalMode)btSwapEndian(bvh->m_traversalMode);
bvh->m_subtreeHeaderCount = btSwapEndian(bvh->m_subtreeHeaderCount);
bvh->m_subtreeHeaderCount = static_cast<int>(btSwapEndian(bvh->m_subtreeHeaderCount));
}
unsigned int calculatedBufSize = bvh->calculateSerializeBufferSize();
@@ -1302,7 +1305,7 @@ btOptimizedBvh *btOptimizedBvh::deSerializeInPlace(void *i_alignedDataBuffer, un
bvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[1] = btSwapEndian(bvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[1]);
bvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[2] = btSwapEndian(bvh->m_quantizedContiguousNodes[nodeIndex].m_quantizedAabbMax[2]);
bvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex = btSwapEndian(bvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex);
bvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex = static_cast<int>(btSwapEndian(bvh->m_quantizedContiguousNodes[nodeIndex].m_escapeIndexOrTriangleIndex));
}
}
nodeData += sizeof(btQuantizedBvhNode) * nodeCount;
@@ -1318,9 +1321,9 @@ btOptimizedBvh *btOptimizedBvh::deSerializeInPlace(void *i_alignedDataBuffer, un
btUnSwapVector3Endian(bvh->m_contiguousNodes[nodeIndex].m_aabbMinOrg);
btUnSwapVector3Endian(bvh->m_contiguousNodes[nodeIndex].m_aabbMaxOrg);
bvh->m_contiguousNodes[nodeIndex].m_escapeIndex = btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_escapeIndex);
bvh->m_contiguousNodes[nodeIndex].m_subPart = btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_subPart);
bvh->m_contiguousNodes[nodeIndex].m_triangleIndex = btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_triangleIndex);
bvh->m_contiguousNodes[nodeIndex].m_escapeIndex = static_cast<int>(btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_escapeIndex));
bvh->m_contiguousNodes[nodeIndex].m_subPart = static_cast<int>(btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_subPart));
bvh->m_contiguousNodes[nodeIndex].m_triangleIndex = static_cast<int>(btSwapEndian(bvh->m_contiguousNodes[nodeIndex].m_triangleIndex));
}
}
nodeData += sizeof(btOptimizedBvhNode) * nodeCount;
@@ -1343,8 +1346,8 @@ btOptimizedBvh *btOptimizedBvh::deSerializeInPlace(void *i_alignedDataBuffer, un
bvh->m_SubtreeHeaders[i].m_quantizedAabbMax[1] = btSwapEndian(bvh->m_SubtreeHeaders[i].m_quantizedAabbMax[1]);
bvh->m_SubtreeHeaders[i].m_quantizedAabbMax[2] = btSwapEndian(bvh->m_SubtreeHeaders[i].m_quantizedAabbMax[2]);
bvh->m_SubtreeHeaders[i].m_rootNodeIndex = btSwapEndian(bvh->m_SubtreeHeaders[i].m_rootNodeIndex);
bvh->m_SubtreeHeaders[i].m_subtreeSize = btSwapEndian(bvh->m_SubtreeHeaders[i].m_subtreeSize);
bvh->m_SubtreeHeaders[i].m_rootNodeIndex = static_cast<int>(btSwapEndian(bvh->m_SubtreeHeaders[i].m_rootNodeIndex));
bvh->m_SubtreeHeaders[i].m_subtreeSize = static_cast<int>(btSwapEndian(bvh->m_SubtreeHeaders[i].m_subtreeSize));
}
}
@@ -1352,7 +1355,7 @@ btOptimizedBvh *btOptimizedBvh::deSerializeInPlace(void *i_alignedDataBuffer, un
}
// Constructor that prevents btVector3's default constructor from being called
btOptimizedBvh::btOptimizedBvh(btOptimizedBvh &self, bool ownsMemory) :
btOptimizedBvh::btOptimizedBvh(btOptimizedBvh &self, bool /* ownsMemory */) :
m_bvhAabbMin(self.m_bvhAabbMin),
m_bvhAabbMax(self.m_bvhAabbMax),
m_bvhQuantization(self.m_bvhQuantization)

View File

@@ -311,10 +311,10 @@ protected:
//This block replaces the block below and uses no branches, and replaces the 8 bit return with a 32 bit return for improved performance (~3x on XBox 360)
SIMD_FORCE_INLINE unsigned testQuantizedAabbAgainstQuantizedAabb(unsigned short int* aabbMin1,unsigned short int* aabbMax1,const unsigned short int* aabbMin2,const unsigned short int* aabbMax2) const
{
return btSelect((unsigned)((aabbMin1[0] <= aabbMax2[0]) & (aabbMax1[0] >= aabbMin2[0])
return static_cast<unsigned int>(btSelect((unsigned)((aabbMin1[0] <= aabbMax2[0]) & (aabbMax1[0] >= aabbMin2[0])
& (aabbMin1[2] <= aabbMax2[2]) & (aabbMax1[2] >= aabbMin2[2])
& (aabbMin1[1] <= aabbMax2[1]) & (aabbMax1[1] >= aabbMin2[1])),
1, 0);
1, 0));
}
#else
SIMD_FORCE_INLINE bool testQuantizedAabbAgainstQuantizedAabb(unsigned short int* aabbMin1,unsigned short int* aabbMax1,const unsigned short int* aabbMin2,const unsigned short int* aabbMax2) const

View File

@@ -81,7 +81,7 @@ btShapeHull::~btShapeHull ()
}
bool
btShapeHull::buildHull (btScalar margin)
btShapeHull::buildHull (btScalar /*margin*/)
{
int numSampleDirections = NUM_UNITSPHERE_POINTS;
{
@@ -107,7 +107,7 @@ btShapeHull::buildHull (btScalar margin)
HullDesc hd;
hd.mFlags = QF_TRIANGLES;
hd.mVcount = numSampleDirections;
hd.mVcount = static_cast<unsigned int>(numSampleDirections);
#ifdef BT_USE_DOUBLE_PRECISION
hd.mVertices = &supportPoints[0];
@@ -124,16 +124,16 @@ btShapeHull::buildHull (btScalar margin)
return false;
}
m_vertices.resize (hr.mNumOutputVertices);
m_vertices.resize (static_cast<int>(hr.mNumOutputVertices));
for (i = 0; i < hr.mNumOutputVertices; i++)
for (i = 0; i < static_cast<int>(hr.mNumOutputVertices); i++)
{
m_vertices[i] = hr.m_OutputVertices[i];
}
m_numIndices = hr.mNumIndices;
m_indices.resize(m_numIndices);
for (i = 0; i < m_numIndices; i++)
m_indices.resize(static_cast<int>(m_numIndices));
for (i = 0; i < static_cast<int>(m_numIndices); i++)
{
m_indices[i] = hr.m_Indices[i];
}
@@ -147,7 +147,7 @@ btShapeHull::buildHull (btScalar margin)
int
btShapeHull::numTriangles () const
{
return m_numIndices / 3;
return static_cast<int>(m_numIndices / 3);
}
int
@@ -159,6 +159,6 @@ btShapeHull::numVertices () const
int
btShapeHull::numIndices () const
{
return m_numIndices;
return static_cast<int>(m_numIndices);
}

View File

@@ -97,7 +97,7 @@ void btTriangleMesh::addTriangle(const btVector3& vertex0,const btVector3& verte
m_indexedMeshes[0].m_triangleIndexBase = (unsigned char*) &m_32bitIndices[0];
} else
{
int curIndex = m_16bitIndices.size();
short curIndex = static_cast<short>(m_16bitIndices.size());
m_16bitIndices.push_back(curIndex++);
m_16bitIndices.push_back(curIndex++);
m_16bitIndices.push_back(curIndex++);
@@ -112,4 +112,4 @@ int btTriangleMesh::getNumTriangles() const
return m_32bitIndices.size() / 3;
}
return m_16bitIndices.size() / 3;
}
}

View File

@@ -602,13 +602,13 @@ GJK gjk(stackAlloc,
wtrs1.getBasis(),wtrs1.getOrigin(),shape1,
radialmargin+EPA_accuracy);
const Z collide(gjk.SearchOrigin());
results.gjk_iterations = gjk.iterations+1;
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 = epa.iterations+1;
results.epa_iterations = static_cast<int>(epa.iterations+1);
if(pd>0)
{
results.status = sResults::Penetrating;

View File

@@ -35,7 +35,7 @@ struct sResults
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 */
EPA_Failed /* EPA phase fail, bigger problem, need to save parameters, and debug */
} status;
btVector3 witnesses[2];
btVector3 normal;

View File

@@ -1,3 +1,27 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2008 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, 2008
*/
#include "BulletCollision/CollisionShapes/btConvexInternalShape.h"
#include "BulletCollision/CollisionShapes/btSphereShape.h"
#include "btGjkEpa2.h"
@@ -364,7 +388,7 @@ static btScalar projectorigin( const btVector3& a,
if((mindist<0)||(subd<mindist))
{
mindist = subd;
m = ((subm&1)?1<<i:0)+((subm&2)?1<<j:0);
m = static_cast<U>(((subm&1)?1<<i:0)+((subm&2)?1<<j:0));
w[i] = subw[0];
w[j] = subw[1];
w[imd3[j]] = 0;
@@ -412,9 +436,9 @@ static btScalar projectorigin( const btVector3& a,
if((mindist<0)||(subd<mindist))
{
mindist = subd;
m = (subm&1?1<<i:0)+
m = static_cast<U>((subm&1?1<<i:0)+
(subm&2?1<<j:0)+
(subm&4?8:0);
(subm&4?8:0));
w[i] = subw[0];
w[j] = subw[1];
w[imd3[j]] = 0;
@@ -476,7 +500,7 @@ struct eStatus { enum _ {
OutOfVertices,
AccuraryReached,
FallBack,
Failed, };};
Failed };};
/* Fields */
eStatus::_ m_status;
GJK::sSimplex m_result;

View File

@@ -1,3 +1,27 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2008 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, 2008
*/
#ifndef _68DA1F85_90B7_4bb0_A705_83B4040A75C6_
#define _68DA1F85_90B7_4bb0_A705_83B4040A75C6_
#include "BulletCollision/CollisionShapes/btConvexShape.h"
@@ -12,7 +36,7 @@ struct sResults
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 */
EPA_Failed /* EPA phase fail, bigger problem, need to save parameters, and debug */
} status;
btVector3 witnesses[2];
btVector3 normal;

View File

@@ -21,6 +21,7 @@ subject to the following restrictions:
#define NUM_UNITSPHERE_POINTS 42
static btVector3 sPenetrationDirections[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] =
{

View File

@@ -157,4 +157,4 @@ btTriangleConvexcastCallback::processTriangle (btVector3* triangle, int partId,
}
}
}
}
}

View File

@@ -35,12 +35,12 @@ public:
virtual ~btConstraintSolver() {}
virtual void prepareSolve (int numBodies, int numManifolds) {;}
virtual void prepareSolve (int /* numBodies */, int /* numManifolds */) {;}
///solve a group of constraints
virtual btScalar solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifold,int numManifolds,btTypedConstraint** constraints,int numConstraints, const btContactSolverInfo& info,class btIDebugDraw* debugDrawer, btStackAlloc* stackAlloc,btDispatcher* dispatcher) = 0;
virtual void allSolved (const btContactSolverInfo& info,class btIDebugDraw* debugDrawer, btStackAlloc* stackAlloc) {;}
virtual void allSolved (const btContactSolverInfo& /* info */,class btIDebugDraw* /* debugDrawer */, btStackAlloc* /* stackAlloc */) {;}
///clear internal cached data and reset random seed
virtual void reset() = 0;

View File

@@ -233,6 +233,12 @@ btScalar resolveSingleFriction(
}
btScalar resolveSingleFrictionOriginal(
btRigidBody& body1,
btRigidBody& body2,
btManifoldPoint& contactPoint,
const btContactSolverInfo& solverInfo);
btScalar resolveSingleFrictionOriginal(
btRigidBody& body1,
btRigidBody& body2,
@@ -400,6 +406,12 @@ btScalar resolveSingleCollisionCombined(
return normalImpulse;
}
btScalar resolveSingleFrictionEmpty(
btRigidBody& body1,
btRigidBody& body2,
btManifoldPoint& contactPoint,
const btContactSolverInfo& solverInfo);
btScalar resolveSingleFrictionEmpty(
btRigidBody& body1,
btRigidBody& body2,

View File

@@ -31,6 +31,7 @@ static const int kAxisA[] = { 1, 0, 0 };
static const int kAxisB[] = { 2, 2, 1 };
#define GENERIC_D6_DISABLE_WARMSTARTING 1
btScalar btGetMatrixElem(const btMatrix3x3& mat, int index);
btScalar btGetMatrixElem(const btMatrix3x3& mat, int index)
{
int i = index%3;
@@ -39,6 +40,7 @@ btScalar btGetMatrixElem(const btMatrix3x3& mat, int index)
}
///MatrixToEulerXYZ from http://www.geometrictools.com/LibFoundation/Mathematics/Wm4Matrix3.inl.html
bool matrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz);
bool matrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz)
{
// // rot = cy*cz -cy*sz sy
@@ -101,13 +103,11 @@ int btRotationalLimitMotor::testLimitValue(btScalar test_value)
m_currentLimit = 2;//High limit violation
m_currentLimitError = test_value - m_hiLimit;
return 2;
}
else
{
m_currentLimit = 0;//Free from violation
return 0;
}
};
m_currentLimit = 0;//Free from violation
return 0;
}

View File

@@ -52,6 +52,7 @@ void btOdeContactJoint::GetInfo1(Info1 *info)
void dPlaneSpace1 (const dVector3 n, dVector3 p, dVector3 q);
void dPlaneSpace1 (const dVector3 n, dVector3 p, dVector3 q)
{
if (btFabs(n[2]) > M_SQRT12) {
@@ -200,16 +201,16 @@ void btOdeContactJoint::GetInfo2(Info2 *info)
info->J1l[s+1] = t1[1];
info->J1l[s+2] = t1[2];
dCROSS (info->J1a+s,=,c1,t1);
if (1) { //j->node[1].body) {
// if (1) { //j->node[1].body) {
info->J2l[s+0] = -t1[0];
info->J2l[s+1] = -t1[1];
info->J2l[s+2] = -t1[2];
dCROSS (info->J2a+s,= -,c2,t1);
}
// }
// set right hand side
if (0) {//j->contact.surface.mode & dContactMotion1) {
// if (0) {//j->contact.surface.mode & dContactMotion1) {
//info->c[1] = j->contact.surface.motion1;
}
// }
// set LCP bounds and friction index. this depends on the approximation
// mode
//1e30f
@@ -217,17 +218,17 @@ void btOdeContactJoint::GetInfo2(Info2 *info)
info->lo[1] = -friction;//-j->contact.surface.mu;
info->hi[1] = friction;//j->contact.surface.mu;
if (1)//j->contact.surface.mode & dContactApprox1_1)
// if (1)//j->contact.surface.mode & dContactApprox1_1)
info->findex[1] = 0;
// set slip (constraint force mixing)
if (0)//j->contact.surface.mode & dContactSlip1)
{
// info->cfm[1] = j->contact.surface.slip1;
} else
{
//info->cfm[1] = 0.f;
}
// if (0)//j->contact.surface.mode & dContactSlip1)
// {
// // info->cfm[1] = j->contact.surface.slip1;
// } else
// {
// //info->cfm[1] = 0.f;
// }
}
// second friction direction
@@ -236,39 +237,39 @@ void btOdeContactJoint::GetInfo2(Info2 *info)
info->J1l[s2+1] = t2[1];
info->J1l[s2+2] = t2[2];
dCROSS (info->J1a+s2,=,c1,t2);
if (1) { //j->node[1].body) {
// if (1) { //j->node[1].body) {
info->J2l[s2+0] = -t2[0];
info->J2l[s2+1] = -t2[1];
info->J2l[s2+2] = -t2[2];
dCROSS (info->J2a+s2,= -,c2,t2);
}
// }
// set right hand side
if (0){//j->contact.surface.mode & dContactMotion2) {
// if (0){//j->contact.surface.mode & dContactMotion2) {
//info->c[2] = j->contact.surface.motion2;
}
// }
// set LCP bounds and friction index. this depends on the approximation
// mode
if (0){//j->contact.surface.mode & dContactMu2) {
// if (0){//j->contact.surface.mode & dContactMu2) {
//info->lo[2] = -j->contact.surface.mu2;
//info->hi[2] = j->contact.surface.mu2;
}
else {
// }
// else {
info->lo[2] = -friction;
info->hi[2] = friction;
}
if (0)//j->contact.surface.mode & dContactApprox1_2)
// }
// if (0)//j->contact.surface.mode & dContactApprox1_2)
{
info->findex[2] = 0;
}
// {
// info->findex[2] = 0;
// }
// set slip (constraint force mixing)
if (0) //j->contact.surface.mode & dContactSlip2)
// if (0) //j->contact.surface.mode & dContactSlip2)
{
// {
//info->cfm[2] = j->contact.surface.slip2;
}
// }
}
#endif //DO_THE_FRICTION_2

View File

@@ -69,14 +69,14 @@ inline btScalar dDOT1 (const btScalar *a, const btScalar *b)
*/
#define dCROSSMAT(A,a,skip,plus,minus) \
do { \
{ \
(A)[1] = minus (a)[2]; \
(A)[2] = plus (a)[1]; \
(A)[(skip)+0] = plus (a)[2]; \
(A)[(skip)+2] = minus (a)[0]; \
(A)[2*(skip)+0] = minus (a)[1]; \
(A)[2*(skip)+1] = plus (a)[0]; \
} while(0)
}
#define dMULTIPLYOP2_333(A,op,B,C) \
@@ -130,9 +130,9 @@ typedef btScalar *dRealMutablePtr;
//#define dRealAllocaArray(name,size) btScalar *name = (btScalar*) stackAlloc->allocate(dEFFICIENT_SIZE(size)*sizeof(btScalar));
#define dRealAllocaArray(name,size) btScalar *name = NULL; \
int memNeeded_##name = dEFFICIENT_SIZE(size)*sizeof(btScalar); \
if (memNeeded_##name < stackAlloc->getAvailableMemory()) name = (btScalar*) stackAlloc->allocate(memNeeded_##name); \
else{ btAssert(memNeeded_##name < stackAlloc->getAvailableMemory()); name = (btScalar*) alloca(memNeeded_##name); }
unsigned int memNeeded_##name = dEFFICIENT_SIZE(size)*sizeof(btScalar); \
if (memNeeded_##name < static_cast<std::size_t>(stackAlloc->getAvailableMemory())) name = (btScalar*) stackAlloc->allocate(memNeeded_##name); \
else{ btAssert(memNeeded_##name < static_cast<std::size_t>(stackAlloc->getAvailableMemory())); name = (btScalar*) alloca(memNeeded_##name); }

View File

@@ -66,7 +66,7 @@ btOdeQuickstepConstraintSolver::btOdeQuickstepConstraintSolver():
//iterative lcp and penalty method
btScalar btOdeQuickstepConstraintSolver::solveGroup(btCollisionObject** bodies,int numBulletBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc,btDispatcher* dispatcher)
btScalar btOdeQuickstepConstraintSolver::solveGroup(btCollisionObject** /*bodies*/,int numBulletBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc,btDispatcher* /*dispatcher*/)
{
m_CurBody = 0;
@@ -155,6 +155,7 @@ btScalar btOdeQuickstepConstraintSolver::solveGroup(btCollisionObject** bodies,i
typedef btScalar dQuaternion[4];
#define _R(i,j) R[(i)*4+(j)]
void dRfromQ1 (dMatrix3 R, const dQuaternion q);
void dRfromQ1 (dMatrix3 R, const dQuaternion q)
{
// q = (s,vx,vy,vz)
@@ -339,7 +340,7 @@ void btOdeQuickstepConstraintSolver::ConvertConstraint(btPersistentManifold* man
void btOdeQuickstepConstraintSolver::ConvertTypedConstraint(
btTypedConstraint * constraint,
btAlignedObjectArray<btOdeJoint*> &joints,int& numJoints,
const btAlignedObjectArray< btOdeSolverBody*> &bodies,int _bodyId0,int _bodyId1,btIDebugDraw* debugDrawer)
const btAlignedObjectArray< btOdeSolverBody*> &bodies,int _bodyId0,int _bodyId1,btIDebugDraw* /*debugDrawer*/)
{
int bodyId0 = _bodyId0,bodyId1 = _bodyId1;

View File

@@ -65,7 +65,7 @@ unsigned long btSequentialImpulseConstraintSolver::btRand2()
int btSequentialImpulseConstraintSolver::btRandInt2 (int n)
{
// seems good; xor-fold and modulus
const unsigned long un = n;
const unsigned long un = static_cast<unsigned long>(n);
unsigned long r = btRand2();
// note: probably more aggressive than it needs to be -- might be
@@ -92,7 +92,7 @@ int btSequentialImpulseConstraintSolver::btRandInt2 (int n)
bool MyContactDestroyedCallback(void* userPersistentData);
bool MyContactDestroyedCallback(void* userPersistentData)
{
assert (userPersistentData);
@@ -127,6 +127,7 @@ btSequentialImpulseConstraintSolver::~btSequentialImpulseConstraintSolver()
}
void initSolverBody(btSolverBody* solverBody, btCollisionObject* collisionObject);
void initSolverBody(btSolverBody* solverBody, btCollisionObject* collisionObject)
{
btRigidBody* rb = btRigidBody::upcast(collisionObject);
@@ -152,6 +153,8 @@ void initSolverBody(btSolverBody* solverBody, btCollisionObject* collisionObject
}
btScalar penetrationResolveFactor = btScalar(0.9);
btScalar restitutionCurve(btScalar rel_vel, btScalar restitution);
btScalar restitutionCurve(btScalar rel_vel, btScalar restitution)
{
btScalar rest = restitution * -rel_vel;
@@ -165,6 +168,13 @@ btScalar restitutionCurve(btScalar rel_vel, btScalar restitution)
//velocity + friction
//response between two dynamic objects with friction
btScalar resolveSingleCollisionCombinedCacheFriendly(
btSolverBody& body1,
btSolverBody& body2,
const btSolverConstraint& contactConstraint,
const btContactSolverInfo& solverInfo);
//SIMD_FORCE_INLINE
btScalar resolveSingleCollisionCombinedCacheFriendly(
btSolverBody& body1,
@@ -230,6 +240,13 @@ btScalar resolveSingleCollisionCombinedCacheFriendly(
#ifndef NO_FRICTION_TANGENTIALS
btScalar resolveSingleFrictionCacheFriendly(
btSolverBody& body1,
btSolverBody& body2,
const btSolverConstraint& contactConstraint,
const btContactSolverInfo& solverInfo,
btScalar appliedNormalImpulse);
//SIMD_FORCE_INLINE
btScalar resolveSingleFrictionCacheFriendly(
btSolverBody& body1,
@@ -430,7 +447,7 @@ void btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3&
btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc)
btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCollisionObject** /*bodies */,int /*numBodies */,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc)
{
BT_PROFILE("solveGroupCacheFriendlySetup");
(void)stackAlloc;
@@ -488,7 +505,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
//todo: use stack allocator for this temp memory
int minReservation = numManifolds*2;
// int minReservation = numManifolds*2;
//m_tmpSolverBodyPool.reserve(minReservation);
@@ -751,7 +768,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
}
btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc)
btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyIterations(btCollisionObject** /*bodies */,int /*numBodies*/,btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* /*debugDrawer*/,btStackAlloc* /*stackAlloc*/)
{
BT_PROFILE("solveGroupCacheFriendlyIterations");
int numConstraintPool = m_tmpSolverConstraintPool.size();
@@ -895,7 +912,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendly(btCollisio
}
/// btSequentialImpulseConstraintSolver Sequentially applies impulses
btScalar btSequentialImpulseConstraintSolver::solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc,btDispatcher* dispatcher)
btScalar btSequentialImpulseConstraintSolver::solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc,btDispatcher* /*dispatcher*/)
{
BT_PROFILE("solveGroup");
if (getSolverMode() & SOLVER_CACHE_FRIENDLY)

View File

@@ -26,7 +26,7 @@ enum btTypedConstraintType
CONETWIST_CONSTRAINT_TYPE,
D6_CONSTRAINT_TYPE,
VEHICLE_CONSTRAINT_TYPE,
SLIDER_CONSTRAINT_TYPE,
SLIDER_CONSTRAINT_TYPE
};
///TypedConstraint is the baseclass for Bullet constraints and vehicles

View File

@@ -231,6 +231,7 @@ void plSetEuler(plReal yaw,plReal pitch,plReal roll, plQuaternion orient)
void plAddVertex(plCollisionShapeHandle cshape, plReal x,plReal y,plReal z)
{
btCollisionShape* colShape = reinterpret_cast<btCollisionShape*>( cshape);
(void)colShape;
btAssert(colShape->getShapeType()==CONVEX_HULL_SHAPE_PROXYTYPE);
btConvexHullShape* convexHullShape = reinterpret_cast<btConvexHullShape*>( cshape);
convexHullShape->addPoint(btPoint3(x,y,z));

View File

@@ -107,7 +107,7 @@ void btContinuousDynamicsWorld::calculateTimeOfImpacts(btScalar timeStep)
///'toi' is the global smallest time of impact. However, we just calculate the time of impact for each object individually.
///so we handle the case moving versus static properly, and we cheat for moving versus moving
float toi = 1.f;
btScalar toi = 1.f;
btDispatcherInfo& dispatchInfo = getDispatchInfo();
@@ -145,12 +145,12 @@ void btContinuousDynamicsWorld::updateTemporalAabbs(btScalar timeStep)
const btVector3& linvel = body->getLinearVelocity();
//make the AABB temporal
float temporalAabbMaxx = temporalAabbMax.getX();
float temporalAabbMaxy = temporalAabbMax.getY();
float temporalAabbMaxz = temporalAabbMax.getZ();
float temporalAabbMinx = temporalAabbMin.getX();
float temporalAabbMiny = temporalAabbMin.getY();
float temporalAabbMinz = temporalAabbMin.getZ();
btScalar temporalAabbMaxx = temporalAabbMax.getX();
btScalar temporalAabbMaxy = temporalAabbMax.getY();
btScalar temporalAabbMaxz = temporalAabbMax.getZ();
btScalar temporalAabbMinx = temporalAabbMin.getX();
btScalar temporalAabbMiny = temporalAabbMin.getY();
btScalar temporalAabbMinz = temporalAabbMin.getZ();
// add linear motion
btVector3 linMotion = linvel*timeStep;

View File

@@ -53,13 +53,16 @@ class btDynamicsWorld : public btCollisionWorld
virtual void debugDrawWorld() = 0;
virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false) { (void)constraint;};
virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false)
{
(void)constraint; (void)disableCollisionsBetweenLinkedBodies;
}
virtual void removeConstraint(btTypedConstraint* constraint) {(void)constraint;};
virtual void removeConstraint(btTypedConstraint* constraint) {(void)constraint;}
virtual void addVehicle(btRaycastVehicle* vehicle) {(void)vehicle;};
virtual void addVehicle(btRaycastVehicle* vehicle) {(void)vehicle;}
virtual void removeVehicle(btRaycastVehicle* vehicle) {(void)vehicle;};
virtual void removeVehicle(btRaycastVehicle* vehicle) {(void)vehicle;}
//once a rigidbody is added to the dynamics world, it will get this gravity assigned
//existing rigidbodies in the world get gravity assigned too, during this method

View File

@@ -27,7 +27,11 @@ subject to the following restrictions:
can be used by probes that are checking whether the
library is actually installed.
*/
extern "C" void btBulletDynamicsProbe () {}
extern "C"
{
void btBulletDynamicsProbe ();
void btBulletDynamicsProbe () {}
}

View File

@@ -486,6 +486,7 @@ struct btWheelContactPoint
};
btScalar calcRollingFriction(btWheelContactPoint& contactPoint);
btScalar calcRollingFriction(btWheelContactPoint& contactPoint)
{

View File

@@ -623,7 +623,7 @@ struct RayCaster : public btDbvt::ICollide
tests = 0;
}
virtual void Process(const btDbvt::Node* a,const btDbvt::Node* b)
virtual void Process(const btDbvt::Node* /*a*/,const btDbvt::Node* /*b*/)
{
}
@@ -1892,11 +1892,11 @@ void btSoftBody::randomizeConstraints()
{
for(int i=0,ni=m_links.size();i<ni;++i)
{
btSwap(m_links[i],m_links[rand()%ni]);
btSwap(m_links[i],m_links[std::rand()%ni]);
}
for(int i=0,ni=m_faces.size();i<ni;++i)
{
btSwap(m_faces[i],m_faces[rand()%ni]);
btSwap(m_faces[i],m_faces[std::rand()%ni]);
}
}
@@ -2540,7 +2540,7 @@ switch(m_cfg.collisions&fCollision::RVSmask)
struct DoCollide : btDbvt::ICollide
{
virtual void Process(const btDbvt::Node* a,const btDbvt::Node* b)
virtual void Process(const btDbvt::Node* /*a*/,const btDbvt::Node* /*b*/)
{
}
@@ -2628,7 +2628,7 @@ switch(cf&fCollision::SVSmask)
{
return false;
}
virtual void Process(const btDbvt::Node* leaf)
virtual void Process(const btDbvt::Node* /*leaf*/)
{
}

View File

@@ -45,13 +45,13 @@ public:
V_TwoSided, ///Vertex normals are fliped to match velocity
V_OneSided, ///Vertex normals are taken as it is
F_TwoSided, ///Face normals are fliped to match velocity
F_OneSided, ///Face normals are taken as it is
F_OneSided ///Face normals are taken as it is
};};
///eVSolver : velocities solvers
struct eVSolver { enum _ {
Linear, ///Linear solver
Volume, ///Volume solver
Volume ///Volume solver
};};
///ePSolver : positions solvers
@@ -60,14 +60,14 @@ public:
Volume, ///Volume solver
Anchors, ///Anchor solver
RContacts, ///Rigid contacts solver
SContacts, ///Soft contacts solver
SContacts ///Soft contacts solver
};};
///eSolverPresets
struct eSolverPresets { enum _ {
Positions,
Velocities,
Default = Positions,
Default = Positions
};};
///eFeature
@@ -76,7 +76,7 @@ public:
Node,
Link,
Face,
Tetra,
Tetra
};};
typedef btAlignedObjectArray<eVSolver::_> tVSolverArray;
@@ -94,14 +94,14 @@ public:
SVSmask = 0x00f0, ///Rigid versus soft mask
VF_SS = 0x0010, ///Vertex vs face soft vs soft handling
/* presets */
Default = SDF_RS,
Default = SDF_RS
};};
///fMaterial
struct fMaterial { enum _ {
DebugDraw = 0x0001, /// Enable debug draw
/* presets */
Default = DebugDraw,
Default = DebugDraw
};};
//

View File

@@ -92,6 +92,7 @@ static inline btScalar tetravolume(const btVector3& x0,
}
//
/*
static btVector3 stresscolor(btScalar stress)
{
static const btVector3 spectrum[]= { btVector3(1,0,1),
@@ -108,7 +109,7 @@ static btVector3 stresscolor(btScalar stress)
const btScalar frc=stress-sel;
return(spectrum[sel]+(spectrum[sel+1]-spectrum[sel])*frc);
}
*/
//
void btSoftBodyHelpers::Draw( btSoftBody* psb,
btIDebugDraw* idraw,
@@ -252,6 +253,7 @@ void btSoftBodyHelpers::Draw( btSoftBody* psb,
}
}
#if 0
//
void btSoftBodyHelpers::DrawInfos( btSoftBody* psb,
btIDebugDraw* idraw,
@@ -277,6 +279,7 @@ void btSoftBodyHelpers::DrawInfos( btSoftBody* psb,
if(text[0]) idraw->draw3dText(n.m_x,text);
}
}
#endif
//
void btSoftBodyHelpers::DrawNodeTree( btSoftBody* psb,
@@ -501,18 +504,18 @@ btSoftBody* btSoftBodyHelpers::CreateFromTriMesh(btSoftBody::btSoftBodyWorldInf
btSoftBody* btSoftBodyHelpers::CreateFromConvexHull(btSoftBody::btSoftBodyWorldInfo& worldInfo, const btVector3* vertices,
int nvertices)
{
HullDesc hdsc(QF_TRIANGLES,nvertices,vertices);
HullDesc hdsc(QF_TRIANGLES,static_cast<unsigned int>(nvertices),vertices);
HullResult hres;
HullLibrary hlib;/*??*/
hdsc.mMaxVertices=nvertices;
hdsc.mMaxVertices=static_cast<unsigned int>(nvertices);
hlib.CreateConvexHull(hdsc,hres);
btSoftBody* psb=new btSoftBody(&worldInfo,(int)hres.mNumOutputVertices,
&hres.m_OutputVertices[0],0);
for(int i=0;i<(int)hres.mNumFaces;++i)
{
const int idx[]={ hres.m_Indices[i*3+0],
hres.m_Indices[i*3+1],
hres.m_Indices[i*3+2]};
const int idx[]={ static_cast<int>(hres.m_Indices[i*3+0]),
static_cast<int>(hres.m_Indices[i*3+1]),
static_cast<int>(hres.m_Indices[i*3+2])};
if(idx[0]<idx[1]) psb->appendLink( idx[0],idx[1]);
if(idx[1]<idx[2]) psb->appendLink( idx[1],idx[2]);
if(idx[2]<idx[0]) psb->appendLink( idx[2],idx[0]);

View File

@@ -37,7 +37,7 @@ struct fDrawFlags { enum _ {
Notes = 0x0080,
/* presets */
Std = Links+Faces+Tetras+Anchors+Notes,
StdTetra = Std-Faces+Tetras,
StdTetra = Std-Faces+Tetras
};};
struct btSoftBodyHelpers
@@ -46,12 +46,14 @@ struct btSoftBodyHelpers
static void Draw( btSoftBody* psb,
btIDebugDraw* idraw,
int drawflags=fDrawFlags::Std);
#if 0
/* Draw body infos */
static void DrawInfos( btSoftBody* psb,
btIDebugDraw* idraw,
bool masses,
bool areas,
bool stress);
#endif
/* Draw node tree */
static void DrawNodeTree( btSoftBody* psb,
btIDebugDraw* idraw,

View File

@@ -105,4 +105,4 @@ btCollisionAlgorithmCreateFunc* btSoftBodyRigidBodyCollisionConfiguration::getCo
///fallback to the regular rigid collision shape
return btDefaultCollisionConfiguration::getCollisionAlgorithmCreateFunc(proxyType0,proxyType1);
}
}

View File

@@ -142,7 +142,7 @@ struct btSparseSdf
const IntFrac iy=Decompose(scx.y());
const IntFrac iz=Decompose(scx.z());
const unsigned h=Hash(ix.b,iy.b,iz.b,shape);
Cell*& root=cells[h%cells.size()];
Cell*& root=cells[static_cast<int>(h%cells.size())];
Cell* c=root;
++nqueries;
while(c)

View File

@@ -120,35 +120,41 @@ void btAlignedFreeInternal (void* ptr)
#else
void* btAlignedAllocInternal (size_t size, int alignment)
{
void *ret;
char *real;
unsigned long offset;
gNumAlignedAllocs++;
void* btAlignedAllocInternal (std::size_t size, int alignment);
real = (char *)malloc(size + sizeof(void *) + (alignment-1));
if (real) {
offset = (alignment - (unsigned long)(real + sizeof(void *))) & (alignment-1);
ret = (void *)((real + sizeof(void *)) + offset);
*((void **)(ret)-1) = (void *)(real);
} else {
ret = (void *)(real);
}
return (ret);
void* btAlignedAllocInternal (std::size_t size, int alignment)
{
void *ret;
char *real;
unsigned long offset;
gNumAlignedAllocs++;
real = (char*) malloc(size + sizeof(void *) + (alignment-1));
if (real != 0)
{
offset = (alignment - (unsigned long)(real + sizeof(void *))) & (alignment-1);
ret = (void *)((real + sizeof(void *)) + offset);
*((void **)(ret)-1) = (void *)(real);
}
else
{
ret = (void *)(real);
}
return (ret);
}
void btAlignedFreeInternal (void* ptr)
{
void* real;
gNumAlignedFree++;
void* real;
gNumAlignedFree++;
if (ptr) {
real = *((void **)(ptr)-1);
free(real);
}
if (ptr != 0)
{
real = *((void **)(ptr)-1);
//::operator delete(real);
free(real);
}
}
#endif //

View File

@@ -35,7 +35,7 @@ void* btAlignedAllocInternal (size_t size, int alignment,int line,char* filename
void btAlignedFreeInternal (void* ptr,int line,char* filename);
#else
void* btAlignedAllocInternal (size_t size, int alignment);
void* btAlignedAllocInternal (std::size_t size, int alignment);
void btAlignedFreeInternal (void* ptr);
#define btAlignedAlloc(a,b) btAlignedAllocInternal(a,b)

View File

@@ -57,6 +57,7 @@ inline int coplanar( const btPlane &a, const btPlane &b ) { return (a==b || a==P
btVector3 PlaneLineIntersection(const btPlane &plane, const btVector3 &p0, const btVector3 &p1);
btVector3 PlaneProject(const btPlane &plane, const btVector3 &point);
btVector3 ThreePlaneIntersection(const btPlane &p0,const btPlane &p1, const btPlane &p2);
btVector3 ThreePlaneIntersection(const btPlane &p0,const btPlane &p1, const btPlane &p2)
{
btVector3 N1 = p0.normal;
@@ -167,13 +168,14 @@ ConvexH::ConvexH(int vertices_size,int edges_size,int facets_size)
}
int PlaneTest(const btPlane &p, const btVector3 &v);
int PlaneTest(const btPlane &p, const btVector3 &v) {
btScalar a = dot(v,p.normal)+p.dist;
int flag = (a>planetestepsilon)?OVER:((a<-planetestepsilon)?UNDER:COPLANAR);
return flag;
}
int SplitTest(ConvexH &convex,const btPlane &plane);
int SplitTest(ConvexH &convex,const btPlane &plane) {
int flag=0;
for(int i=0;i<convex.vertices.size();i++) {
@@ -233,6 +235,7 @@ int maxdirfiltered(const T *p,int count,const T &dir,btAlignedObjectArray<int> &
return m;
}
btVector3 orth(const btVector3 &v);
btVector3 orth(const btVector3 &v)
{
btVector3 a=cross(v,btVector3(0,0,1));
@@ -295,6 +298,7 @@ int maxdirsterid(const T *p,int count,const T &dir,btAlignedObjectArray<int> &al
int operator ==(const int3 &a,const int3 &b);
int operator ==(const int3 &a,const int3 &b)
{
for(int i=0;i<3;i++)
@@ -305,12 +309,13 @@ int operator ==(const int3 &a,const int3 &b)
}
int above(btVector3* vertices,const int3& t, const btVector3 &p, btScalar epsilon);
int above(btVector3* vertices,const int3& t, const btVector3 &p, btScalar epsilon)
{
btVector3 n=TriNormal(vertices[t[0]],vertices[t[1]],vertices[t[2]]);
return (dot(n,p-vertices[t[0]]) > epsilon); // EPSILON???
}
int hasedge(const int3 &t, int a,int b);
int hasedge(const int3 &t, int a,int b)
{
for(int i=0;i<3;i++)
@@ -320,10 +325,12 @@ int hasedge(const int3 &t, int a,int b)
}
return 0;
}
int hasvert(const int3 &t, int v);
int hasvert(const int3 &t, int v)
{
return (t[0]==v || t[1]==v || t[2]==v) ;
}
int shareedge(const int3 &a,const int3 &b);
int shareedge(const int3 &a,const int3 &b)
{
int i;
@@ -398,6 +405,8 @@ void HullLibrary::removeb2b(Tri* s,Tri*t)
void HullLibrary::checkit(Tri *t)
{
(void)t;
int i;
btAssert(m_tris[t->id]==t);
for(i=0;i<3;i++)
@@ -406,6 +415,13 @@ void HullLibrary::checkit(Tri *t)
int i2=(i+2)%3;
int a = (*t)[i1];
int b = (*t)[i2];
// release compile fix
(void)i1;
(void)i2;
(void)a;
(void)b;
btAssert(a!=b);
btAssert( m_tris[t->n[i]]->neib(b,a) == t->id);
}
@@ -552,7 +568,7 @@ int HullLibrary::calchullgen(btVector3 *verts,int verts_count, int vlimit)
}
Tri *te;
vlimit-=4;
while(vlimit >0 && (te=extrudable(epsilon)))
while(vlimit >0 && ((te=extrudable(epsilon)) != 0))
{
int3 ti=*te;
int v=te->vmax;
@@ -627,7 +643,7 @@ int HullLibrary::calchull(btVector3 *verts,int verts_count, TUIntArray& tris_out
for (i=0;i<ts.size();i++)
{
tris_out[i] = ts[i];
tris_out[i] = static_cast<unsigned int>(ts[i]);
}
m_tris.resize(0);
@@ -642,7 +658,7 @@ bool HullLibrary::ComputeHull(unsigned int vcount,const btVector3 *vertices,PHul
{
int tris_count;
int ret = calchull( (btVector3 *) vertices, (int) vcount, result.m_Indices, tris_count, vlimit );
int ret = calchull( (btVector3 *) vertices, (int) vcount, result.m_Indices, tris_count, static_cast<int>(vlimit) );
if(!ret) return false;
result.mIndexCount = (unsigned int) (tris_count*3);
result.mFaceCount = (unsigned int) tris_count;
@@ -653,6 +669,7 @@ bool HullLibrary::ComputeHull(unsigned int vcount,const btVector3 *vertices,PHul
}
void ReleaseHull(PHullResult &result);
void ReleaseHull(PHullResult &result)
{
if ( result.m_Indices.size() )
@@ -690,7 +707,7 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, //
if ( vcount < 8 ) vcount = 8;
btAlignedObjectArray<btVector3> vertexSource;
vertexSource.resize(vcount);
vertexSource.resize(static_cast<int>(vcount));
btVector3 scale;
@@ -702,11 +719,11 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, //
{
if ( 1 ) // scale vertices back to their original size.
// if ( 1 ) // scale vertices back to their original size.
{
for (unsigned int i=0; i<ovcount; i++)
{
btVector3& v = vertexSource[i];
btVector3& v = vertexSource[static_cast<int>(i)];
v[0]*=scale[0];
v[1]*=scale[1];
v[2]*=scale[2];
@@ -720,7 +737,7 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, //
// re-index triangle mesh so it refers to only used vertices, rebuild a new vertex table.
btAlignedObjectArray<btVector3> vertexScratch;
vertexScratch.resize(hr.mVcount);
vertexScratch.resize(static_cast<int>(hr.mVcount));
BringOutYourDead(hr.mVertices,hr.mVcount, &vertexScratch[0], ovcount, &hr.m_Indices[0], hr.mIndexCount );
@@ -730,11 +747,11 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, //
{
result.mPolygons = false;
result.mNumOutputVertices = ovcount;
result.m_OutputVertices.resize(ovcount);
result.m_OutputVertices.resize(static_cast<int>(ovcount));
result.mNumFaces = hr.mFaceCount;
result.mNumIndices = hr.mIndexCount;
result.m_Indices.resize(hr.mIndexCount);
result.m_Indices.resize(static_cast<int>(hr.mIndexCount));
memcpy(&result.m_OutputVertices[0], &vertexScratch[0], sizeof(btVector3)*ovcount );
@@ -763,13 +780,13 @@ HullError HullLibrary::CreateConvexHull(const HullDesc &desc, //
{
result.mPolygons = true;
result.mNumOutputVertices = ovcount;
result.m_OutputVertices.resize(ovcount);
result.m_OutputVertices.resize(static_cast<int>(ovcount));
result.mNumFaces = hr.mFaceCount;
result.mNumIndices = hr.mIndexCount+hr.mFaceCount;
result.m_Indices.resize(result.mNumIndices);
result.m_Indices.resize(static_cast<int>(result.mNumIndices));
memcpy(&result.m_OutputVertices[0], &vertexScratch[0], sizeof(btVector3)*ovcount );
if ( 1 )
// if ( 1 )
{
const unsigned int *source = &hr.m_Indices[0];
unsigned int *dest = &result.m_Indices[0];
@@ -829,7 +846,7 @@ static void addPoint(unsigned int &vcount,btVector3 *p,btScalar x,btScalar y,btS
vcount++;
}
btScalar GetDist(btScalar px,btScalar py,btScalar pz,const btScalar *p2);
btScalar GetDist(btScalar px,btScalar py,btScalar pz,const btScalar *p2)
{
@@ -871,7 +888,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
const char *vtx = (const char *) svertices;
if ( 1 )
// if ( 1 )
{
for (unsigned int i=0; i<svcount; i++)
{
@@ -979,7 +996,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
pz = pz*recip[2]; // normalize
}
if ( 1 )
// if ( 1 )
{
unsigned int j;
@@ -1028,7 +1045,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
}
// ok..now make sure we didn't prune so many vertices it is now invalid.
if ( 1 )
// if ( 1 )
{
btScalar bmin[3] = { FLT_MAX, FLT_MAX, FLT_MAX };
btScalar bmax[3] = { -FLT_MAX, -FLT_MAX, -FLT_MAX };
@@ -1100,7 +1117,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
void HullLibrary::BringOutYourDead(const btVector3* verts,unsigned int vcount, btVector3* overts,unsigned int &ocount,unsigned int *indices,unsigned indexcount)
{
TUIntArray usedIndices;
usedIndices.resize(vcount);
usedIndices.resize(static_cast<int>(vcount));
memset(&usedIndices[0],0,sizeof(unsigned int)*vcount);
ocount = 0;
@@ -1111,9 +1128,9 @@ void HullLibrary::BringOutYourDead(const btVector3* verts,unsigned int vcount, b
btAssert( v >= 0 && v < vcount );
if ( usedIndices[v] ) // if already remapped
if ( usedIndices[static_cast<int>(v)] ) // if already remapped
{
indices[i] = usedIndices[v]-1; // index to new array
indices[i] = usedIndices[static_cast<int>(v)]-1; // index to new array
}
else
{
@@ -1128,7 +1145,7 @@ void HullLibrary::BringOutYourDead(const btVector3* verts,unsigned int vcount, b
btAssert( ocount >=0 && ocount <= vcount );
usedIndices[v] = ocount; // assign new index remapping
usedIndices[static_cast<int>(v)] = ocount; // assign new index remapping
}
}

View File

@@ -22,7 +22,12 @@ subject to the following restrictions:
can be used by probes that are checking whether the
library is actually installed.
*/
extern "C" void btBulletMathProbe () {}
extern "C"
{
void btBulletMathProbe ();
void btBulletMathProbe () {}
}
bool btGeometryUtil::isPointInsidePlanes(const btAlignedObjectArray<btVector3>& planeEquations, const btVector3& point, btScalar margin)
@@ -57,6 +62,8 @@ bool btGeometryUtil::areVerticesBehindPlane(const btVector3& planeNormal, const
return true;
}
bool notExist(const btVector3& planeEquation,const btAlignedObjectArray<btVector3>& planeEquations);
bool notExist(const btVector3& planeEquation,const btAlignedObjectArray<btVector3>& planeEquations)
{
int numbrushes = planeEquations.size();

View File

@@ -298,4 +298,4 @@ class btHashMap
};
#endif //BT_HASH_MAP_H
#endif //BT_HASH_MAP_H

View File

@@ -56,11 +56,11 @@ class btIDebugDraw
virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)=0;
virtual void drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& n0,const btVector3& n1,const btVector3& n2,const btVector3& color, btScalar alpha)
virtual void drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& /*n0*/,const btVector3& /*n1*/,const btVector3& /*n2*/,const btVector3& color, btScalar alpha)
{
drawTriangle(v0,v1,v2,color,alpha);
}
virtual void drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& color, btScalar alpha)
virtual void drawTriangle(const btVector3& v0,const btVector3& v1,const btVector3& v2,const btVector3& color, btScalar /*alpha*/)
{
drawLine(v0,v1,color);
drawLine(v1,v2,color);

View File

@@ -33,7 +33,7 @@ public:
:m_elemSize(elemSize),
m_maxElements(maxElements)
{
m_pool = (unsigned char*) btAlignedAlloc(m_elemSize*m_maxElements,16);
m_pool = (unsigned char*) btAlignedAlloc( static_cast<unsigned int>(m_elemSize*m_maxElements),16);
unsigned char* p = m_pool;
m_firstFree = p;
@@ -58,6 +58,8 @@ public:
void* allocate(int size)
{
// release mode fix
(void)size;
btAssert(!size || size<=m_elemSize);
btAssert(m_freeCount>0);
void* result = m_firstFree;

View File

@@ -44,9 +44,11 @@ inline int btGetVersion()
#define ATTRIBUTE_ALIGNED128(a) a
#else
#define BT_HAS_ALIGNED_ALLOCATOR
#pragma warning(disable:4530)
#pragma warning(disable:4996)
#pragma warning(disable:4786)
#pragma warning(disable : 4324) // disable padding warning
// #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning.
// #pragma warning(disable:4996) //Turn off warnings about deprecated C routines
// #pragma warning(disable:4786) // Disable the "debug name too long" warning
#define SIMD_FORCE_INLINE __forceinline
#define ATTRIBUTE_ALIGNED16(a) __declspec(align(16)) a
#define ATTRIBUTE_ALIGNED128(a) __declspec (align(128)) a
@@ -142,9 +144,9 @@ typedef float btScalar;
#define BT_DECLARE_ALIGNED_ALLOCATOR() \
SIMD_FORCE_INLINE void* operator new(size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \
SIMD_FORCE_INLINE void* operator new(std::size_t sizeInBytes) { return btAlignedAlloc(sizeInBytes,16); } \
SIMD_FORCE_INLINE void operator delete(void* ptr) { btAlignedFree(ptr); } \
SIMD_FORCE_INLINE void* operator new(size_t, void* ptr) { return ptr; } \
SIMD_FORCE_INLINE void* operator new(std::size_t, void* ptr) { return ptr; } \
SIMD_FORCE_INLINE void operator delete(void*, void*) { } \
@@ -289,7 +291,7 @@ SIMD_FORCE_INLINE int btSelect(unsigned condition, int valueIfConditionNonZero,
{
unsigned testNz = (unsigned)(((int)condition | -(int)condition) >> 31);
unsigned testEqz = ~testNz;
return ((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz));
return static_cast<int>((valueIfConditionNonZero & testNz) | (valueIfConditionZero & testEqz));
}
SIMD_FORCE_INLINE float btSelect(unsigned condition, float valueIfConditionNonZero, float valueIfConditionZero)
{
@@ -316,7 +318,7 @@ SIMD_FORCE_INLINE unsigned btSwapEndian(unsigned val)
SIMD_FORCE_INLINE unsigned short btSwapEndian(unsigned short val)
{
return (((val & 0xff00) >> 8) | ((val & 0x00ff) << 8));
return static_cast<unsigned short>(((val & 0xff00) >> 8) | ((val & 0x00ff) << 8));
}
SIMD_FORCE_INLINE unsigned btSwapEndian(int val)
@@ -337,7 +339,7 @@ SIMD_FORCE_INLINE unsigned short btSwapEndian(short val)
///so instead of returning a float/double, we return integer/long long integer
SIMD_FORCE_INLINE unsigned int btSwapEndianFloat(float d)
{
unsigned int a;
unsigned int a = 0;
unsigned char *dst = (unsigned char *)&a;
unsigned char *src = (unsigned char *)&d;
@@ -351,7 +353,7 @@ SIMD_FORCE_INLINE unsigned int btSwapEndianFloat(float d)
// unswap using char pointers
SIMD_FORCE_INLINE float btUnswapEndianFloat(unsigned int a)
{
float d;
float d = 0.0f;
unsigned char *src = (unsigned char *)&a;
unsigned char *dst = (unsigned char *)&d;
@@ -383,7 +385,7 @@ SIMD_FORCE_INLINE void btSwapEndianDouble(double d, unsigned char* dst)
// unswap using char pointers
SIMD_FORCE_INLINE double btUnswapEndianDouble(const unsigned char *src)
{
double d;
double d = 0.0;
unsigned char *dst = (unsigned char *)&d;
dst[0] = src[7];

View File

@@ -61,7 +61,7 @@ public:
int getAvailableMemory() const
{
return totalsize - usedsize;
return static_cast<int>(totalsize - usedsize);
}
unsigned char* allocate(unsigned int size)