move static globals inside static member functions, to avoid hassle with C#/CLI/C++ managed code, compile error C3820
This commit is contained in:
@@ -21,52 +21,6 @@ subject to the following restrictions:
|
||||
|
||||
#define NUM_UNITSPHERE_POINTS 42
|
||||
|
||||
static btVector3 btUnitSpherePoints[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] =
|
||||
{
|
||||
btVector3(btScalar(0.000000) , btScalar(-0.000000),btScalar(-1.000000)),
|
||||
btVector3(btScalar(0.723608) , btScalar(-0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(-0.850649),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.894426) , btScalar(-0.000000),btScalar(-0.447216)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(0.850649),btScalar(-0.447220)),
|
||||
btVector3(btScalar(0.723608) , btScalar(0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(-0.850649),btScalar(0.447220)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(-0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(0.850649),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.894426) , btScalar(0.000000),btScalar(0.447216)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(0.000000),btScalar(1.000000)),
|
||||
btVector3(btScalar(0.425323) , btScalar(-0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(-0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.262869) , btScalar(-0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.425323) , btScalar(0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.850648) , btScalar(-0.000000),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.525730) , btScalar(-0.000000),btScalar(-0.850652)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(-0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(0.262869) , btScalar(0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.951058) , btScalar(0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.951058) , btScalar(-0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.000000) , btScalar(-1.000000),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(-0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(1.000000),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.688190) , btScalar(-0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(-0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(-0.850648) , btScalar(0.000000),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(0.688190) , btScalar(0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(0.525730) , btScalar(0.000000),btScalar(0.850652)),
|
||||
btVector3(btScalar(0.162456) , btScalar(-0.499995),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(-0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
|
||||
};
|
||||
|
||||
btShapeHull::btShapeHull (const btConvexShape* shape)
|
||||
{
|
||||
m_shape = shape;
|
||||
@@ -93,7 +47,7 @@ btShapeHull::buildHull (btScalar /*margin*/)
|
||||
{
|
||||
btVector3 norm;
|
||||
m_shape->getPreferredPenetrationDirection(i,norm);
|
||||
btUnitSpherePoints[numSampleDirections] = norm;
|
||||
getUnitSpherePoints()[numSampleDirections] = norm;
|
||||
numSampleDirections++;
|
||||
}
|
||||
}
|
||||
@@ -103,7 +57,7 @@ btShapeHull::buildHull (btScalar /*margin*/)
|
||||
int i;
|
||||
for (i = 0; i < numSampleDirections; i++)
|
||||
{
|
||||
supportPoints[i] = m_shape->localGetSupportingVertex(btUnitSpherePoints[i]);
|
||||
getUnitSpherePoints()[i] = m_shape->localGetSupportingVertex(getUnitSpherePoints()[i]);
|
||||
}
|
||||
|
||||
HullDesc hd;
|
||||
@@ -163,3 +117,54 @@ btShapeHull::numIndices () const
|
||||
return static_cast<int>(m_numIndices);
|
||||
}
|
||||
|
||||
|
||||
btVector3* btShapeHull::getUnitSpherePoints()
|
||||
{
|
||||
static btVector3 sUnitSpherePoints[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] =
|
||||
{
|
||||
btVector3(btScalar(0.000000) , btScalar(-0.000000),btScalar(-1.000000)),
|
||||
btVector3(btScalar(0.723608) , btScalar(-0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(-0.850649),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.894426) , btScalar(-0.000000),btScalar(-0.447216)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(0.850649),btScalar(-0.447220)),
|
||||
btVector3(btScalar(0.723608) , btScalar(0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(-0.850649),btScalar(0.447220)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(-0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(0.850649),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.894426) , btScalar(0.000000),btScalar(0.447216)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(0.000000),btScalar(1.000000)),
|
||||
btVector3(btScalar(0.425323) , btScalar(-0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(-0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.262869) , btScalar(-0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.425323) , btScalar(0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.850648) , btScalar(-0.000000),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.525730) , btScalar(-0.000000),btScalar(-0.850652)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(-0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(0.262869) , btScalar(0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.951058) , btScalar(0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.951058) , btScalar(-0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.000000) , btScalar(-1.000000),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(-0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(1.000000),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.688190) , btScalar(-0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(-0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(-0.850648) , btScalar(0.000000),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(0.688190) , btScalar(0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(0.525730) , btScalar(0.000000),btScalar(0.850652)),
|
||||
btVector3(btScalar(0.162456) , btScalar(-0.499995),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(-0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
|
||||
};
|
||||
return sUnitSpherePoints;
|
||||
}
|
||||
|
||||
|
||||
@@ -27,6 +27,15 @@ subject to the following restrictions:
|
||||
///It approximates the convex hull using the supporting vertex of 42 directions.
|
||||
class btShapeHull
|
||||
{
|
||||
protected:
|
||||
|
||||
btAlignedObjectArray<btVector3> m_vertices;
|
||||
btAlignedObjectArray<unsigned int> m_indices;
|
||||
unsigned int m_numIndices;
|
||||
const btConvexShape* m_shape;
|
||||
|
||||
static btVector3* getUnitSpherePoints();
|
||||
|
||||
public:
|
||||
btShapeHull (const btConvexShape* shape);
|
||||
~btShapeHull ();
|
||||
@@ -45,12 +54,6 @@ public:
|
||||
{
|
||||
return &m_indices[0];
|
||||
}
|
||||
|
||||
protected:
|
||||
btAlignedObjectArray<btVector3> m_vertices;
|
||||
btAlignedObjectArray<unsigned int> m_indices;
|
||||
unsigned int m_numIndices;
|
||||
const btConvexShape* m_shape;
|
||||
};
|
||||
|
||||
#endif //_SHAPE_HULL_H
|
||||
|
||||
@@ -20,51 +20,6 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
|
||||
#define NUM_UNITSPHERE_POINTS 42
|
||||
static btVector3 sPenetrationDirections[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] =
|
||||
{
|
||||
btVector3(btScalar(0.000000) , btScalar(-0.000000),btScalar(-1.000000)),
|
||||
btVector3(btScalar(0.723608) , btScalar(-0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(-0.850649),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.894426) , btScalar(-0.000000),btScalar(-0.447216)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(0.850649),btScalar(-0.447220)),
|
||||
btVector3(btScalar(0.723608) , btScalar(0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(-0.850649),btScalar(0.447220)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(-0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(0.850649),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.894426) , btScalar(0.000000),btScalar(0.447216)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(0.000000),btScalar(1.000000)),
|
||||
btVector3(btScalar(0.425323) , btScalar(-0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(-0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.262869) , btScalar(-0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.425323) , btScalar(0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.850648) , btScalar(-0.000000),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.525730) , btScalar(-0.000000),btScalar(-0.850652)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(-0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(0.262869) , btScalar(0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.951058) , btScalar(0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.951058) , btScalar(-0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.000000) , btScalar(-1.000000),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(-0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(1.000000),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.688190) , btScalar(-0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(-0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(-0.850648) , btScalar(0.000000),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(0.688190) , btScalar(0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(0.525730) , btScalar(0.000000),btScalar(0.850652)),
|
||||
btVector3(btScalar(0.162456) , btScalar(-0.499995),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(-0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
|
||||
};
|
||||
|
||||
|
||||
bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& simplexSolver,
|
||||
@@ -133,7 +88,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
|
||||
for (i=0;i<numSampleDirections;i++)
|
||||
{
|
||||
btVector3 norm = sPenetrationDirections[i];
|
||||
btVector3 norm = getPenetrationDirections()[i];
|
||||
seperatingAxisInABatch[i] = (-norm) * transA.getBasis() ;
|
||||
seperatingAxisInBBatch[i] = norm * transB.getBasis() ;
|
||||
}
|
||||
@@ -147,7 +102,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
btVector3 norm;
|
||||
convexA->getPreferredPenetrationDirection(i,norm);
|
||||
norm = transA.getBasis() * norm;
|
||||
sPenetrationDirections[numSampleDirections] = norm;
|
||||
getPenetrationDirections()[numSampleDirections] = norm;
|
||||
seperatingAxisInABatch[numSampleDirections] = (-norm) * transA.getBasis();
|
||||
seperatingAxisInBBatch[numSampleDirections] = norm * transB.getBasis();
|
||||
numSampleDirections++;
|
||||
@@ -164,7 +119,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
btVector3 norm;
|
||||
convexB->getPreferredPenetrationDirection(i,norm);
|
||||
norm = transB.getBasis() * norm;
|
||||
sPenetrationDirections[numSampleDirections] = norm;
|
||||
getPenetrationDirections()[numSampleDirections] = norm;
|
||||
seperatingAxisInABatch[numSampleDirections] = (-norm) * transA.getBasis();
|
||||
seperatingAxisInBBatch[numSampleDirections] = norm * transB.getBasis();
|
||||
numSampleDirections++;
|
||||
@@ -180,7 +135,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
|
||||
for (i=0;i<numSampleDirections;i++)
|
||||
{
|
||||
btVector3 norm = sPenetrationDirections[i];
|
||||
btVector3 norm = getPenetrationDirections()[i];
|
||||
if (check2d)
|
||||
{
|
||||
norm[2] = 0.f;
|
||||
@@ -228,7 +183,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
btVector3 norm;
|
||||
convexA->getPreferredPenetrationDirection(i,norm);
|
||||
norm = transA.getBasis() * norm;
|
||||
sPenetrationDirections[numSampleDirections] = norm;
|
||||
getPenetrationDirections()[numSampleDirections] = norm;
|
||||
numSampleDirections++;
|
||||
}
|
||||
}
|
||||
@@ -243,7 +198,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
btVector3 norm;
|
||||
convexB->getPreferredPenetrationDirection(i,norm);
|
||||
norm = transB.getBasis() * norm;
|
||||
sPenetrationDirections[numSampleDirections] = norm;
|
||||
getPenetrationDirections()[numSampleDirections] = norm;
|
||||
numSampleDirections++;
|
||||
}
|
||||
}
|
||||
@@ -252,7 +207,7 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
|
||||
for (int i=0;i<numSampleDirections;i++)
|
||||
{
|
||||
const btVector3& norm = sPenetrationDirections[i];
|
||||
const btVector3& norm = getPenetrationDirections()[i];
|
||||
seperatingAxisInA = (-norm)* transA.getBasis();
|
||||
seperatingAxisInB = norm* transB.getBasis();
|
||||
pInA = convexA->localGetSupportVertexWithoutMarginNonVirtual(seperatingAxisInA);
|
||||
@@ -353,5 +308,55 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
|
||||
return res.m_hasResult;
|
||||
}
|
||||
|
||||
btVector3* btMinkowskiPenetrationDepthSolver::getPenetrationDirections()
|
||||
{
|
||||
static btVector3 sPenetrationDirections[NUM_UNITSPHERE_POINTS+MAX_PREFERRED_PENETRATION_DIRECTIONS*2] =
|
||||
{
|
||||
btVector3(btScalar(0.000000) , btScalar(-0.000000),btScalar(-1.000000)),
|
||||
btVector3(btScalar(0.723608) , btScalar(-0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(-0.850649),btScalar(-0.447219)),
|
||||
btVector3(btScalar(-0.894426) , btScalar(-0.000000),btScalar(-0.447216)),
|
||||
btVector3(btScalar(-0.276388) , btScalar(0.850649),btScalar(-0.447220)),
|
||||
btVector3(btScalar(0.723608) , btScalar(0.525725),btScalar(-0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(-0.850649),btScalar(0.447220)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(-0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(-0.723608) , btScalar(0.525725),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.276388) , btScalar(0.850649),btScalar(0.447219)),
|
||||
btVector3(btScalar(0.894426) , btScalar(0.000000),btScalar(0.447216)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(0.000000),btScalar(1.000000)),
|
||||
btVector3(btScalar(0.425323) , btScalar(-0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(-0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.262869) , btScalar(-0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.425323) , btScalar(0.309011),btScalar(-0.850654)),
|
||||
btVector3(btScalar(0.850648) , btScalar(-0.000000),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.525730) , btScalar(-0.000000),btScalar(-0.850652)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(-0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(-0.162456) , btScalar(0.499995),btScalar(-0.850654)),
|
||||
btVector3(btScalar(-0.688190) , btScalar(0.499997),btScalar(-0.525736)),
|
||||
btVector3(btScalar(0.262869) , btScalar(0.809012),btScalar(-0.525738)),
|
||||
btVector3(btScalar(0.951058) , btScalar(0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.951058) , btScalar(-0.309013),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(0.000000) , btScalar(-1.000000),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(-0.809017),btScalar(0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(-0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.951058) , btScalar(0.309013),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(-0.000000) , btScalar(1.000000),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.587786) , btScalar(0.809017),btScalar(-0.000000)),
|
||||
btVector3(btScalar(0.688190) , btScalar(-0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(-0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(-0.850648) , btScalar(0.000000),btScalar(0.525736)),
|
||||
btVector3(btScalar(-0.262869) , btScalar(0.809012),btScalar(0.525738)),
|
||||
btVector3(btScalar(0.688190) , btScalar(0.499997),btScalar(0.525736)),
|
||||
btVector3(btScalar(0.525730) , btScalar(0.000000),btScalar(0.850652)),
|
||||
btVector3(btScalar(0.162456) , btScalar(-0.499995),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(-0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(-0.425323) , btScalar(0.309011),btScalar(0.850654)),
|
||||
btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
|
||||
};
|
||||
|
||||
return sPenetrationDirections;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -22,6 +22,10 @@ subject to the following restrictions:
|
||||
///Implementation is based on sampling the depth using support mapping, and using GJK step to get the witness points.
|
||||
class btMinkowskiPenetrationDepthSolver : public btConvexPenetrationDepthSolver
|
||||
{
|
||||
protected:
|
||||
|
||||
static btVector3* getPenetrationDirections();
|
||||
|
||||
public:
|
||||
|
||||
virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver,
|
||||
|
||||
@@ -23,8 +23,6 @@ subject to the following restrictions:
|
||||
#include "LinearMath/btDefaultMotionState.h"
|
||||
#include "btKinematicCharacterController.h"
|
||||
|
||||
static btVector3 upAxisDirection[3] = { btVector3(1.0f, 0.0f, 0.0f), btVector3(0.0f, 1.0f, 0.0f), btVector3(0.0f, 0.0f, 1.0f) };
|
||||
|
||||
|
||||
// static helper method
|
||||
static btVector3
|
||||
@@ -189,13 +187,13 @@ void btKinematicCharacterController::stepUp ( btCollisionWorld* world)
|
||||
{
|
||||
// phase 1: up
|
||||
btTransform start, end;
|
||||
m_targetPosition = m_currentPosition + upAxisDirection[m_upAxis] * m_stepHeight;
|
||||
m_targetPosition = m_currentPosition + getUpAxisDirections()[m_upAxis] * m_stepHeight;
|
||||
|
||||
start.setIdentity ();
|
||||
end.setIdentity ();
|
||||
|
||||
/* FIXME: Handle penetration properly */
|
||||
start.setOrigin (m_currentPosition + upAxisDirection[m_upAxis] * btScalar(0.1f));
|
||||
start.setOrigin (m_currentPosition + getUpAxisDirections()[m_upAxis] * btScalar(0.1f));
|
||||
end.setOrigin (m_targetPosition);
|
||||
|
||||
btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject);
|
||||
@@ -355,8 +353,8 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld
|
||||
btTransform start, end;
|
||||
|
||||
// phase 3: down
|
||||
btVector3 step_drop = upAxisDirection[m_upAxis] * m_currentStepOffset;
|
||||
btVector3 gravity_drop = upAxisDirection[m_upAxis] * m_stepHeight;
|
||||
btVector3 step_drop = getUpAxisDirections()[m_upAxis] * m_currentStepOffset;
|
||||
btVector3 gravity_drop = getUpAxisDirections()[m_upAxis] * m_stepHeight;
|
||||
m_targetPosition -= (step_drop + gravity_drop);
|
||||
|
||||
start.setIdentity ();
|
||||
@@ -545,3 +543,11 @@ bool btKinematicCharacterController::onGround () const
|
||||
void btKinematicCharacterController::debugDraw(btIDebugDraw* debugDrawer)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
btVector3* btKinematicCharacterController::getUpAxisDirections()
|
||||
{
|
||||
static btVector3 sUpAxisDirection[3] = { btVector3(1.0f, 0.0f, 0.0f), btVector3(0.0f, 1.0f, 0.0f), btVector3(0.0f, 0.0f, 1.0f) };
|
||||
|
||||
return sUpAxisDirection;
|
||||
}
|
||||
@@ -35,6 +35,7 @@ class btPairCachingGhostObject;
|
||||
class btKinematicCharacterController : public btCharacterControllerInterface
|
||||
{
|
||||
protected:
|
||||
|
||||
btScalar m_halfHeight;
|
||||
|
||||
btPairCachingGhostObject* m_ghostObject;
|
||||
@@ -69,7 +70,9 @@ protected:
|
||||
bool m_useWalkDirection;
|
||||
btScalar m_velocityTimeInterval;
|
||||
int m_upAxis;
|
||||
|
||||
|
||||
static btVector3* getUpAxisDirections();
|
||||
|
||||
btVector3 computeReflectionDirection (const btVector3& direction, const btVector3& normal);
|
||||
btVector3 parallelComponent (const btVector3& direction, const btVector3& normal);
|
||||
btVector3 perpindicularComponent (const btVector3& direction, const btVector3& normal);
|
||||
|
||||
@@ -20,11 +20,21 @@ class btIDebugDraw;
|
||||
class btCollisionWorld;
|
||||
|
||||
#include "LinearMath/btScalar.h"
|
||||
#include "btRigidBody.h"
|
||||
|
||||
///Basic interface to allow actions such as vehicles and characters to be updated inside a btDynamicsWorld
|
||||
class btActionInterface
|
||||
{
|
||||
public:
|
||||
protected:
|
||||
|
||||
static btRigidBody& getFixedBody()
|
||||
{
|
||||
static btRigidBody s_fixed(0, 0,0);
|
||||
s_fixed.setMassProps(btScalar(0.),btVector3(btScalar(0.),btScalar(0.),btScalar(0.)));
|
||||
return s_fixed;
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
virtual ~btActionInterface()
|
||||
{
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
|
||||
|
||||
static btRigidBody s_fixedObject( 0,0,0);
|
||||
|
||||
|
||||
btRaycastVehicle::btRaycastVehicle(const btVehicleTuning& tuning,btRigidBody* chassis, btVehicleRaycaster* raycaster )
|
||||
:m_vehicleRaycaster(raycaster),
|
||||
@@ -187,7 +187,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 = &getFixedBody();///@todo for driving on dynamic/movable objects!;
|
||||
//wheel.m_raycastInfo.m_groundObject = object;
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user