Removed obsolete btPoint3: use btVector3 instead

This commit is contained in:
erwin.coumans
2008-10-27 19:56:48 +00:00
parent 52a151f5e4
commit 6f28170422
77 changed files with 215 additions and 261 deletions

View File

@@ -278,7 +278,7 @@ class BspLoader
enum
{
BSP_LITTLE_ENDIAN = 0,
BSP_BIG_ENDIAN = 1,
BSP_BIG_ENDIAN = 1
};
//returns machines big endian / little endian

View File

@@ -104,8 +104,8 @@ int shapeIndex[maxNumObjects];
#define CUBE_HALF_EXTENTS 0.5
#define EXTRA_HEIGHT -10.f
//GL_LineSegmentShape shapeE(btPoint3(-50,0,0),
// btPoint3(50,0,0));
//GL_LineSegmentShape shapeE(btVector3(-50,0,0),
// btVector3(50,0,0));
void CcdPhysicsDemo::createStack( btCollisionShape* boxShape, float halfCubeSize, int size, float zPos )

View File

@@ -241,7 +241,7 @@ void CollisionDemo::displayCallback(void) {
}
simplex.setSimplexSolver(&sGjkSimplexSolver);
btPoint3 ybuf[4],pbuf[4],qbuf[4];
btVector3 ybuf[4],pbuf[4],qbuf[4];
int numpoints = sGjkSimplexSolver.getSimplex(pbuf,qbuf,ybuf);
simplex.reset();

View File

@@ -68,9 +68,6 @@ void CollisionInterfaceDemo::initPhysics()
objects[0].getWorldTransform().setBasis(basisA);
objects[1].getWorldTransform().setBasis(basisB);
//btPoint3 points0[3]={btPoint3(1,0,0),btPoint3(0,1,0),btPoint3(0,0,1)};
//btPoint3 points1[5]={btPoint3(1,0,0),btPoint3(0,1,0),btPoint3(0,0,1),btPoint3(0,0,-1),btPoint3(-1,-1,0)};
btBoxShape* boxA = new btBoxShape(btVector3(1,1,1));
btBoxShape* boxB = new btBoxShape(btVector3(0.5,0.5,0.5));
//ConvexHullShape hullA(points0,3);

View File

@@ -99,13 +99,11 @@ void btContinuousConvexCollisionDemo::initPhysics()
btVector3 boxHalfExtentsA(10,1,1);
btVector3 boxHalfExtentsB(1.1f,1.1f,1.1f);
btBoxShape* boxA = new btBoxShape(boxHalfExtentsA);
// btBU_Simplex1to4* boxA = new btBU_Simplex1to4(btPoint3(-2,0,-2),btPoint3(2,0,-2),btPoint3(0,0,2),btPoint3(0,2,0));
// btBU_Simplex1to4* boxA = new btBU_Simplex1to4(btPoint3(-12,0,0),btPoint3(12,0,0));
// btBU_Simplex1to4* boxA = new btBU_Simplex1to4(btVector3(-2,0,-2),btVector3(2,0,-2),btVector3(0,0,2),btVector3(0,2,0));
// btBU_Simplex1to4* boxA = new btBU_Simplex1to4(btVector3(-12,0,0),btVector3(12,0,0));
btBoxShape* boxB = new btBoxShape(boxHalfExtentsB);
// btBU_Simplex1to4 boxB(btPoint3(0,10,0),btPoint3(0,-10,0));
shapePtr[0] = boxA;
shapePtr[1] = boxB;

View File

@@ -321,7 +321,7 @@ void ConvexDecompositionDemo::initPhysics(const char* filename)
btConvexHullShape* convexShape = new btConvexHullShape();
for (i=0;i<hull->numVertices();i++)
{
convexShape->addPoint(btPoint3(hull->getVertexPointer()[i]));
convexShape->addPoint(hull->getVertexPointer()[i]);
}
delete tmpConvexShape;

View File

@@ -264,8 +264,8 @@ void MotorDemo::initPhysics()
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
btPoint3 worldAabbMin(-10000,-10000,-10000);
btPoint3 worldAabbMax(10000,10000,10000);
btVector3 worldAabbMin(-10000,-10000,-10000);
btVector3 worldAabbMax(10000,10000,10000);
m_broadphase = new btAxisSweep3 (worldAabbMin, worldAabbMax);
m_solver = new btSequentialImpulseConstraintSolver;

View File

@@ -68,8 +68,8 @@ void GenericJointDemo::initPhysics()
btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collision_config);
btPoint3 worldAabbMin(-10000,-10000,-10000);
btPoint3 worldAabbMax(10000,10000,10000);
btVector3 worldAabbMin(-10000,-10000,-10000);
btVector3 worldAabbMax(10000,10000,10000);
btBroadphaseInterface* overlappingPairCache = new btAxisSweep3 (worldAabbMin, worldAabbMax);
#ifdef USE_ODE_QUICKSTEP

View File

@@ -87,8 +87,8 @@ static int shapeIndex[maxNumObjects];
#define CUBE_HALF_EXTENTS 0.5
#define EXTRA_HEIGHT -10.f
//GL_LineSegmentShape shapeE(btPoint3(-50,0,0),
// btPoint3(50,0,0));
//GL_LineSegmentShape shapeE(btVector3(-50,0,0),
// btVector3(50,0,0));
void MultiThreadedDemo::createStack( btCollisionShape* boxShape, float halfCubeSize, int size, float zPos )

View File

@@ -1,6 +1,5 @@
#include "GLDebugDrawer.h"
#include "LinearMath/btPoint3.h"
#ifdef WIN32 //needed for glut.h
#include <windows.h>

View File

@@ -657,7 +657,7 @@ void GL_ShapeDrawer::drawOpenGL(btScalar* m, const btCollisionShape* shape, cons
int i;
for (i=0;i<polyshape->getNumVertices();i++)
{
btPoint3 vtx;
btVector3 vtx;
polyshape->getVertex(i,vtx);
glRasterPos3f(vtx.x(), vtx.y(), vtx.z());
char buf[12];
@@ -668,7 +668,7 @@ void GL_ShapeDrawer::drawOpenGL(btScalar* m, const btCollisionShape* shape, cons
for (i=0;i<polyshape->getNumPlanes();i++)
{
btVector3 normal;
btPoint3 vtx;
btVector3 vtx;
polyshape->getPlane(normal,vtx,i);
btScalar d = vtx.dot(normal);

View File

@@ -56,7 +56,7 @@ void GL_Simplex1to4::calcClosest(btScalar* m)
for (int i=0;i<m_numVertices;i++)
{
v = tr(m_vertices[i]);
m_simplexSolver->addVertex(v,v,btPoint3(0.f,0.f,0.f));
m_simplexSolver->addVertex(v,v,btVector3(0.f,0.f,0.f));
res = m_simplexSolver->closest(v);
}

View File

@@ -318,8 +318,8 @@ void RagdollDemo::initPhysics()
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
btPoint3 worldAabbMin(-10000,-10000,-10000);
btPoint3 worldAabbMax(10000,10000,10000);
btVector3 worldAabbMin(-10000,-10000,-10000);
btVector3 worldAabbMax(10000,10000,10000);
m_broadphase = new btAxisSweep3 (worldAabbMin, worldAabbMax);
m_solver = new btSequentialImpulseConstraintSolver;

View File

@@ -109,10 +109,10 @@ void SimplexDemo::initPhysics()
simplex.setSimplexSolver(&simplexSolver);
simplex.addVertex(btPoint3(-2,0,-2));
simplex.addVertex(btPoint3(2,0,-2));
simplex.addVertex(btPoint3(0,0,2));
simplex.addVertex(btPoint3(0,2,0));
simplex.addVertex(btVector3(-2,0,-2));
simplex.addVertex(btVector3(2,0,-2));
simplex.addVertex(btVector3(0,0,2));
simplex.addVertex(btVector3(0,2,0));
shapePtr[0] = &simplex;

View File

@@ -2173,7 +2173,7 @@ ColladaConverter::updateRigidBodyVelocity (btRigidBody* body)
void
ColladaConverter::updateConstraint (btTypedConstraint* constraint, domRigid_constraint* rigidConstraint)
{
if (!constraint->getConstraintType() != D6_CONSTRAINT_TYPE)
if (constraint->getConstraintType() != D6_CONSTRAINT_TYPE)
return;
btGeneric6DofConstraint* g6c = (btGeneric6DofConstraint*)constraint;
@@ -2711,7 +2711,7 @@ btCollisionShape* ColladaConverter::getCollisionShape(int shapeIndex)
void ColladaConverter::deleteAllocatedCollisionShapes()
{
int i;
for (int i=0;i<m_allocatedCollisionShapes.size();i++)
for (i=0;i<m_allocatedCollisionShapes.size();i++)
{
delete m_allocatedCollisionShapes[i];
}
@@ -3006,7 +3006,7 @@ void ColladaConverter::ConvertRigidBodyRef( btRigidBodyInput& rbInput,btRigidBod
domFloat fl0 = listFloats.get(vertIndex);
domFloat fl1 = listFloats.get(vertIndex+1);
domFloat fl2 = listFloats.get(vertIndex+2);
convexHull->addPoint(btPoint3(fl0,fl1,fl2) * m_unitMeterScaling);
convexHull->addPoint(btVector3(fl0,fl1,fl2) * m_unitMeterScaling);
}
}
}
@@ -3104,7 +3104,7 @@ void ColladaConverter::ConvertRigidBodyRef( btRigidBodyInput& rbInput,btRigidBod
domFloat fl2 = listFloats.get(k+2);
//printf("float %f %f %f\n",fl0,fl1,fl2);
convexHullShape->addPoint(btPoint3(fl0,fl1,fl2) * m_unitMeterScaling);
convexHullShape->addPoint(btVector3(fl0,fl1,fl2) * m_unitMeterScaling);
}
}
@@ -3149,7 +3149,7 @@ void ColladaConverter::ConvertRigidBodyRef( btRigidBodyInput& rbInput,btRigidBod
domFloat fl2 = listFloats.get(k+2);
//printf("float %f %f %f\n",fl0,fl1,fl2);
convexHullShape->addPoint(btPoint3(fl0,fl1,fl2)*m_unitMeterScaling);
convexHullShape->addPoint(btVector3(fl0,fl1,fl2)*m_unitMeterScaling);
}
}
@@ -3370,7 +3370,7 @@ void ColladaConverter::registerRigidBody(btRigidBody* body, const char* name)
btTypedConstraint* constraint = body->getConstraintRef (i);
// not support by the dom
if (!constraint->getConstraintType() != D6_CONSTRAINT_TYPE)
if (constraint->getConstraintType() != D6_CONSTRAINT_TYPE)
continue;
btRigidConstraintColladaInfo* rcci = findRigidConstraintColladaInfo(constraint);

View File

@@ -27,7 +27,7 @@ class btCollisionShape;
class btRigidBody;
class btTypedConstraint;
class btDynamicsWorld;
class ConstraintInput;
struct ConstraintInput;
class btRigidBodyColladaInfo;
class btRigidBodyColladaInfo

View File

@@ -213,7 +213,7 @@ namespace ConvexDecomposition
unsigned int depth);
};
}
#endif

View File

@@ -118,7 +118,7 @@ protected:
{
//apply the scaling
btVector3 const& scale = m_ch_shape->getLocalScaling();
btPoint3 const* points = m_ch_shape->getPoints();
btVector3 const* points = m_ch_shape->getPoints();
for(int i = 0; i < m_ch_shape->getNumPoints(); ++i) {
m_vertices[i] = vec3f(scale.x() * points[i].x(), scale.y() * points[i].y(), scale.z() * points[i].z());
}

View File

@@ -316,7 +316,7 @@ void rigidBodyArrayNode::draw( M3dView & view, const MDagPath &path,
if(style == M3dView::kFlatShaded ||
style == M3dView::kGouraudShaded) {
glEnable(GL_LIGHTING);
float material[] = { 0.4, 0.3, 1.0, 1.0 };
float material[] = { 0.4f, 0.3f, 1.0f, 1.0f };
glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, material);
for(size_t i = 0; i < m_rigid_bodies.size(); ++i) {
glPushMatrix();
@@ -433,15 +433,15 @@ void rigidBodyArrayNode::computeRigidBodyParam(const MPlug& plug, MDataBlock& da
MPlug(thisObject, ca_rigidBodies).getValue(update);
double mass = data.inputValue(ia_mass).asDouble();
float mass = data.inputValue(ia_mass).asFloat();
vec3f inertia;
if(!m_rigid_bodies.empty()) {
inertia = mass * m_rigid_bodies[0]->collision_shape()->local_inertia();
}
double restitution = data.inputValue(ia_restitution).asDouble();
double friction = data.inputValue(ia_friction).asDouble();
double linearDamping = data.inputValue(ia_linearDamping).asDouble();
double angularDamping = data.inputValue(ia_angularDamping).asDouble();
float restitution = data.inputValue(ia_restitution).asFloat();
float friction = data.inputValue(ia_friction).asFloat();
float linearDamping = data.inputValue(ia_linearDamping).asFloat();
float angularDamping = data.inputValue(ia_angularDamping).asFloat();
for(size_t i = 0; i < m_rigid_bodies.size(); ++i) {
m_rigid_bodies[i]->set_mass(mass);

View File

@@ -21,7 +21,7 @@
#include <assert.h>
btAxisSweep3::btAxisSweep3(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, unsigned short int maxHandles, btOverlappingPairCache* pairCache, bool disableRaycastAccelerator)
btAxisSweep3::btAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned short int maxHandles, btOverlappingPairCache* pairCache, bool disableRaycastAccelerator)
:btAxisSweep3Internal<unsigned short int>(worldAabbMin,worldAabbMax,0xfffe,0xffff,maxHandles,pairCache,disableRaycastAccelerator)
{
// 1 handle is reserved as sentinel
@@ -30,7 +30,7 @@ btAxisSweep3::btAxisSweep3(const btPoint3& worldAabbMin,const btPoint3& worldAab
}
bt32BitAxisSweep3::bt32BitAxisSweep3(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, unsigned int maxHandles , btOverlappingPairCache* pairCache , bool disableRaycastAccelerator)
bt32BitAxisSweep3::bt32BitAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned int maxHandles , btOverlappingPairCache* pairCache , bool disableRaycastAccelerator)
:btAxisSweep3Internal<unsigned int>(worldAabbMin,worldAabbMax,0xfffffffe,0x7fffffff,maxHandles,pairCache,disableRaycastAccelerator)
{
// 1 handle is reserved as sentinel

View File

@@ -19,7 +19,6 @@
#ifndef AXIS_SWEEP_3_H
#define AXIS_SWEEP_3_H
#include "LinearMath/btPoint3.h"
#include "LinearMath/btVector3.h"
#include "btOverlappingPairCache.h"
#include "btBroadphaseInterface.h"
@@ -71,8 +70,8 @@ public:
protected:
btPoint3 m_worldAabbMin; // overall system bounds
btPoint3 m_worldAabbMax; // overall system bounds
btVector3 m_worldAabbMin; // overall system bounds
btVector3 m_worldAabbMax; // overall system bounds
btVector3 m_quantize; // scaling factor for quantization
@@ -122,7 +121,7 @@ protected:
public:
btAxisSweep3Internal(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, BP_FP_INT_TYPE handleMask, BP_FP_INT_TYPE handleSentinel, BP_FP_INT_TYPE maxHandles = 16384, btOverlappingPairCache* pairCache=0,bool disableRaycastAccelerator = false);
btAxisSweep3Internal(const btVector3& worldAabbMin,const btVector3& worldAabbMax, BP_FP_INT_TYPE handleMask, BP_FP_INT_TYPE handleSentinel, BP_FP_INT_TYPE maxHandles = 16384, btOverlappingPairCache* pairCache=0,bool disableRaycastAccelerator = false);
virtual ~btAxisSweep3Internal();
@@ -133,9 +132,9 @@ public:
virtual void calculateOverlappingPairs(btDispatcher* dispatcher);
BP_FP_INT_TYPE addHandle(const btPoint3& aabbMin,const btPoint3& aabbMax, void* pOwner,short int collisionFilterGroup,short int collisionFilterMask,btDispatcher* dispatcher,void* multiSapProxy);
BP_FP_INT_TYPE addHandle(const btVector3& aabbMin,const btVector3& aabbMax, void* pOwner,short int collisionFilterGroup,short int collisionFilterMask,btDispatcher* dispatcher,void* multiSapProxy);
void removeHandle(BP_FP_INT_TYPE handle,btDispatcher* dispatcher);
void updateHandle(BP_FP_INT_TYPE handle, const btPoint3& aabbMin,const btPoint3& aabbMax,btDispatcher* dispatcher);
void updateHandle(BP_FP_INT_TYPE handle, const btVector3& aabbMin,const btVector3& aabbMax,btDispatcher* dispatcher);
SIMD_FORCE_INLINE Handle* getHandle(BP_FP_INT_TYPE index) const {return m_pHandles + index;}
void processAllOverlappingPairs(btOverlapCallback* callback);
@@ -148,7 +147,7 @@ public:
virtual void rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback);
void quantize(BP_FP_INT_TYPE* out, const btPoint3& point, int isMax) const;
void quantize(BP_FP_INT_TYPE* out, const btVector3& point, int isMax) const;
///unQuantize should be conservative: aabbMin/aabbMax should be larger then 'getAabb' result
void unQuantize(btBroadphaseProxy* proxy,btVector3& aabbMin, btVector3& aabbMax ) const;
@@ -319,7 +318,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::unQuantize(btBroadphaseProxy* proxy,b
template <typename BP_FP_INT_TYPE>
btAxisSweep3Internal<BP_FP_INT_TYPE>::btAxisSweep3Internal(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, BP_FP_INT_TYPE handleMask, BP_FP_INT_TYPE handleSentinel,BP_FP_INT_TYPE userMaxHandles, btOverlappingPairCache* pairCache , bool disableRaycastAccelerator)
btAxisSweep3Internal<BP_FP_INT_TYPE>::btAxisSweep3Internal(const btVector3& worldAabbMin,const btVector3& worldAabbMax, BP_FP_INT_TYPE handleMask, BP_FP_INT_TYPE handleSentinel,BP_FP_INT_TYPE userMaxHandles, btOverlappingPairCache* pairCache , bool disableRaycastAccelerator)
:m_bpHandleMask(handleMask),
m_handleSentinel(handleSentinel),
m_pairCache(pairCache),
@@ -420,12 +419,12 @@ btAxisSweep3Internal<BP_FP_INT_TYPE>::~btAxisSweep3Internal()
}
template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::quantize(BP_FP_INT_TYPE* out, const btPoint3& point, int isMax) const
void btAxisSweep3Internal<BP_FP_INT_TYPE>::quantize(BP_FP_INT_TYPE* out, const btVector3& point, int isMax) const
{
#ifdef OLD_CLAMPING_METHOD
///problem with this clamping method is that the floating point during quantization might still go outside the range [(0|isMax) .. (m_handleSentinel&m_bpHandleMask]|isMax]
///see http://code.google.com/p/bullet/issues/detail?id=87
btPoint3 clampedPoint(point);
btVector3 clampedPoint(point);
clampedPoint.setMax(m_worldAabbMin);
clampedPoint.setMin(m_worldAabbMax);
btVector3 v = (clampedPoint - m_worldAabbMin) * m_quantize;
@@ -466,7 +465,7 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::freeHandle(BP_FP_INT_TYPE handle)
template <typename BP_FP_INT_TYPE>
BP_FP_INT_TYPE btAxisSweep3Internal<BP_FP_INT_TYPE>::addHandle(const btPoint3& aabbMin,const btPoint3& aabbMax, void* pOwner,short int collisionFilterGroup,short int collisionFilterMask,btDispatcher* dispatcher,void* multiSapProxy)
BP_FP_INT_TYPE btAxisSweep3Internal<BP_FP_INT_TYPE>::addHandle(const btVector3& aabbMin,const btVector3& aabbMax, void* pOwner,short int collisionFilterGroup,short int collisionFilterMask,btDispatcher* dispatcher,void* multiSapProxy)
{
// quantize the bounds
BP_FP_INT_TYPE min[3], max[3];
@@ -705,7 +704,7 @@ bool btAxisSweep3Internal<BP_FP_INT_TYPE>::testOverlap2D(const Handle* pHandleA,
}
template <typename BP_FP_INT_TYPE>
void btAxisSweep3Internal<BP_FP_INT_TYPE>::updateHandle(BP_FP_INT_TYPE handle, const btPoint3& aabbMin,const btPoint3& aabbMax,btDispatcher* dispatcher)
void btAxisSweep3Internal<BP_FP_INT_TYPE>::updateHandle(BP_FP_INT_TYPE handle, const btVector3& aabbMin,const btVector3& aabbMax,btDispatcher* dispatcher)
{
// assert(bounds.IsFinite());
//assert(bounds.HasVolume());
@@ -984,7 +983,7 @@ class btAxisSweep3 : public btAxisSweep3Internal<unsigned short int>
{
public:
btAxisSweep3(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, unsigned short int maxHandles = 16384, btOverlappingPairCache* pairCache = 0, bool disableRaycastAccelerator = false);
btAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned short int maxHandles = 16384, btOverlappingPairCache* pairCache = 0, bool disableRaycastAccelerator = false);
};
@@ -995,7 +994,7 @@ class bt32BitAxisSweep3 : public btAxisSweep3Internal<unsigned int>
{
public:
bt32BitAxisSweep3(const btPoint3& worldAabbMin,const btPoint3& worldAabbMax, unsigned int maxHandles = 1500000, btOverlappingPairCache* pairCache = 0, bool disableRaycastAccelerator = false);
bt32BitAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned int maxHandles = 1500000, btOverlappingPairCache* pairCache = 0, bool disableRaycastAccelerator = false);
};

View File

@@ -21,7 +21,6 @@ subject to the following restrictions:
#include "btBroadphaseProxy.h"
#include "btOverlappingPairCallback.h"
#include "LinearMath/btPoint3.h"
#include "LinearMath/btAlignedObjectArray.h"
class btDispatcher;

View File

@@ -29,7 +29,7 @@ struct btSimpleBroadphaseProxy : public btBroadphaseProxy
btSimpleBroadphaseProxy() {};
btSimpleBroadphaseProxy(const btPoint3& minpt,const btPoint3& maxpt,int shapeType,void* userPtr,short int collisionFilterGroup,short int collisionFilterMask,void* multiSapProxy)
btSimpleBroadphaseProxy(const btVector3& minpt,const btVector3& maxpt,int shapeType,void* userPtr,short int collisionFilterGroup,short int collisionFilterMask,void* multiSapProxy)
:btBroadphaseProxy(minpt,maxpt,userPtr,collisionFilterGroup,collisionFilterMask,multiSapProxy)
{
(void)shapeType;

View File

@@ -140,8 +140,8 @@ bool SphereTriangleDetector::collide(const btVector3& sphereCenter,btVector3 &po
btVector3 nearestOnEdge;
for (int i = 0; i < m_triangle->getNumEdges(); i++) {
btPoint3 pa;
btPoint3 pb;
btVector3 pa;
btVector3 pb;
m_triangle->getEdge(i,pa,pb);

View File

@@ -17,7 +17,7 @@ subject to the following restrictions:
#define SPHERE_TRIANGLE_DETECTOR_H
#include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h"
#include "LinearMath/btPoint3.h"
class btSphereShape;

View File

@@ -128,7 +128,7 @@ void btCollisionWorld::updateAabbs()
//only update aabb of active objects
if (colObj->isActive())
{
btPoint3 minAabb,maxAabb;
btVector3 minAabb,maxAabb;
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
//need to increase the aabb for contact thresholds
btVector3 contactThreshold(gContactBreakingThreshold,gContactBreakingThreshold,gContactBreakingThreshold);

View File

@@ -19,7 +19,7 @@ subject to the following restrictions:
#include "btPolyhedralConvexShape.h"
#include "btCollisionMargin.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "LinearMath/btPoint3.h"
#include "LinearMath/btVector3.h"
#include "LinearMath/btMinMax.h"
///The btBoxShape is a box primitive around the origin, its sides axis aligned with length specified by half extents, in local shape coordinates. When used as part of a btCollisionObject or btRigidBody it will be an oriented box in world space.
@@ -117,7 +117,7 @@ public:
virtual void calculateLocalInertia(btScalar mass,btVector3& inertia) const;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i ) const
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i ) const
{
//this plane might not be aligned...
btVector4 plane ;
@@ -190,7 +190,7 @@ public:
}
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const
//virtual void getEdge(int i,Edge& edge) const
{
int edgeVert0 = 0;
@@ -261,7 +261,7 @@ public:
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const
virtual bool isInside(const btVector3& pt,btScalar tolerance) const
{
btVector3 halfExtents = getHalfExtentsWithoutMargin();

View File

@@ -49,7 +49,7 @@ public:
halfExtents[m_upAxis] = getRadius() + getHalfHeight();
halfExtents += btVector3(getMargin(),getMargin(),getMargin());
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
aabbMin = center - extent;

View File

@@ -19,7 +19,6 @@ subject to the following restrictions:
#include "LinearMath/btTransform.h"
#include "LinearMath/btVector3.h"
#include "LinearMath/btMatrix3x3.h"
#include "LinearMath/btPoint3.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" //for the shape types
///The btCollisionShape class provides an interface for collision shapes that can be shared among btCollisionObjects.

View File

@@ -141,7 +141,7 @@ void btCompoundShape::getAabb(const btTransform& trans,btVector3& aabbMin,btVect
btMatrix3x3 abs_b = trans.getBasis().absolute();
btPoint3 center = trans(localCenter);
btVector3 center = trans(localCenter);
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
abs_b[1].dot(localHalfExtents),

View File

@@ -14,7 +14,6 @@ subject to the following restrictions:
*/
#include "btConeShape.h"
#include "LinearMath/btPoint3.h"

View File

@@ -28,7 +28,7 @@ btConvexHullShape ::btConvexHullShape (const btScalar* points,int numPoints,int
for (int i=0;i<numPoints;i++)
{
btPoint3* point = (btPoint3*)(pointsBaseAddress + i*stride);
btVector3* point = (btVector3*)(pointsBaseAddress + i*stride);
m_points[i] = point[0];
}
@@ -44,7 +44,7 @@ void btConvexHullShape::setLocalScaling(const btVector3& scaling)
recalcLocalAabb();
}
void btConvexHullShape::addPoint(const btPoint3& point)
void btConvexHullShape::addPoint(const btVector3& point)
{
m_points.push_back(point);
recalcLocalAabb();
@@ -70,7 +70,7 @@ btVector3 btConvexHullShape::localGetSupportingVertexWithoutMargin(const btVecto
for (int i=0;i<m_points.size();i++)
{
btPoint3 vtx = m_points[i] * m_localScaling;
btVector3 vtx = m_points[i] * m_localScaling;
newDot = vec.dot(vtx);
if (newDot > maxDot)
@@ -94,7 +94,7 @@ void btConvexHullShape::batchedUnitVectorGetSupportingVertexWithoutMargin(const
}
for (int i=0;i<m_points.size();i++)
{
btPoint3 vtx = m_points[i] * m_localScaling;
btVector3 vtx = m_points[i] * m_localScaling;
for (int j=0;j<numVectors;j++)
{
@@ -153,7 +153,7 @@ int btConvexHullShape::getNumEdges() const
return m_points.size();
}
void btConvexHullShape::getEdge(int i,btPoint3& pa,btPoint3& pb) const
void btConvexHullShape::getEdge(int i,btVector3& pa,btVector3& pb) const
{
int index0 = i%m_points.size();
@@ -162,7 +162,7 @@ void btConvexHullShape::getEdge(int i,btPoint3& pa,btPoint3& pb) const
pb = m_points[index1]*m_localScaling;
}
void btConvexHullShape::getVertex(int i,btPoint3& vtx) const
void btConvexHullShape::getVertex(int i,btVector3& vtx) const
{
vtx = m_points[i]*m_localScaling;
}
@@ -172,14 +172,14 @@ int btConvexHullShape::getNumPlanes() const
return 0;
}
void btConvexHullShape::getPlane(btVector3& ,btPoint3& ,int ) const
void btConvexHullShape::getPlane(btVector3& ,btVector3& ,int ) const
{
btAssert(0);
}
//not yet
bool btConvexHullShape::isInside(const btPoint3& ,btScalar ) const
bool btConvexHullShape::isInside(const btVector3& ,btScalar ) const
{
assert(0);
return false;

View File

@@ -24,7 +24,7 @@ subject to the following restrictions:
///Bullet provides a general and fast collision detector for convex shapes based on GJK and EPA using localGetSupportingVertex.
ATTRIBUTE_ALIGNED16(class) btConvexHullShape : public btPolyhedralConvexShape
{
btAlignedObjectArray<btPoint3> m_points;
btAlignedObjectArray<btVector3> m_points;
public:
BT_DECLARE_ALIGNED_ALLOCATOR();
@@ -33,16 +33,16 @@ public:
///this constructor optionally takes in a pointer to points. Each point is assumed to be 3 consecutive btScalar (x,y,z), the striding defines the number of bytes between each point, in memory.
///It is easier to not pass any points in the constructor, and just add one point at a time, using addPoint.
///btConvexHullShape make an internal copy of the points.
btConvexHullShape(const btScalar* points=0,int numPoints=0, int stride=sizeof(btPoint3));
btConvexHullShape(const btScalar* points=0,int numPoints=0, int stride=sizeof(btVector3));
void addPoint(const btPoint3& point);
void addPoint(const btVector3& point);
btPoint3* getPoints()
btVector3* getPoints()
{
return &m_points[0];
}
const btPoint3* getPoints() const
const btVector3* getPoints() const
{
return &m_points[0];
}
@@ -64,11 +64,11 @@ public:
virtual int getNumVertices() const;
virtual int getNumEdges() const;
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const;
virtual void getVertex(int i,btPoint3& vtx) const;
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const;
virtual void getVertex(int i,btVector3& vtx) const;
virtual int getNumPlanes() const;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i ) const;
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const;
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i ) const;
virtual bool isInside(const btVector3& pt,btScalar tolerance) const;
///in case we receive negative scaling
virtual void setLocalScaling(const btVector3& scaling);

View File

@@ -43,7 +43,7 @@ btVector3 btConvexPointCloudShape::localGetSupportingVertexWithoutMargin(const b
for (int i=0;i<m_numPoints;i++)
{
btPoint3 vtx = m_points[i] * m_localScaling;
btVector3 vtx = m_points[i] * m_localScaling;
newDot = vec.dot(vtx);
if (newDot > maxDot)
@@ -67,7 +67,7 @@ void btConvexPointCloudShape::batchedUnitVectorGetSupportingVertexWithoutMargin(
}
for (int i=0;i<m_numPoints;i++)
{
btPoint3 vtx = m_points[i] * m_localScaling;
btVector3 vtx = m_points[i] * m_localScaling;
for (int j=0;j<numVectors;j++)
{
@@ -126,12 +126,12 @@ int btConvexPointCloudShape::getNumEdges() const
return 0;
}
void btConvexPointCloudShape::getEdge(int i,btPoint3& pa,btPoint3& pb) const
void btConvexPointCloudShape::getEdge(int i,btVector3& pa,btVector3& pb) const
{
btAssert (0);
}
void btConvexPointCloudShape::getVertex(int i,btPoint3& vtx) const
void btConvexPointCloudShape::getVertex(int i,btVector3& vtx) const
{
vtx = m_points[i]*m_localScaling;
}
@@ -141,14 +141,14 @@ int btConvexPointCloudShape::getNumPlanes() const
return 0;
}
void btConvexPointCloudShape::getPlane(btVector3& ,btPoint3& ,int ) const
void btConvexPointCloudShape::getPlane(btVector3& ,btVector3& ,int ) const
{
btAssert(0);
}
//not yet
bool btConvexPointCloudShape::isInside(const btPoint3& ,btScalar ) const
bool btConvexPointCloudShape::isInside(const btVector3& ,btScalar ) const
{
assert(0);
return false;

View File

@@ -47,12 +47,12 @@ public:
recalcLocalAabb();
}
btPoint3* getPoints()
btVector3* getPoints()
{
return m_points;
}
const btPoint3* getPoints() const
const btVector3* getPoints() const
{
return m_points;
}
@@ -74,11 +74,11 @@ public:
virtual int getNumVertices() const;
virtual int getNumEdges() const;
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const;
virtual void getVertex(int i,btPoint3& vtx) const;
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const;
virtual void getVertex(int i,btVector3& vtx) const;
virtual int getNumPlanes() const;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i ) const;
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const;
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i ) const;
virtual bool isInside(const btVector3& pt,btScalar tolerance) const;
///in case we receive negative scaling
virtual void setLocalScaling(const btVector3& scaling);

View File

@@ -41,7 +41,7 @@ static btVector3 convexHullSupport (const btVector3& localDir, const btVector3*
for (int i=0;i<numPoints;i++)
{
btPoint3 vtx = points[i];// * m_localScaling;
btVector3 vtx = points[i];// * m_localScaling;
newDot = vec.dot(vtx);
if (newDot > maxDot)
@@ -210,7 +210,7 @@ btVector3 btConvexShape::localGetSupportVertexWithoutMarginNonVirtual (const btV
case CONVEX_HULL_SHAPE_PROXYTYPE:
{
btConvexHullShape* convexHullShape = (btConvexHullShape*)this;
btPoint3* points = convexHullShape->getPoints ();
btVector3* points = convexHullShape->getPoints ();
int numPoints = convexHullShape->getNumPoints ();
return convexHullSupport (localDir, points, numPoints);
}
@@ -226,7 +226,7 @@ btVector3 btConvexShape::localGetSupportVertexWithoutMarginNonVirtual (const btV
// should never reach here
btAssert (0);
return btPoint3 (btScalar(0.0f), btScalar(0.0f), btScalar(0.0f));
return btVector3 (btScalar(0.0f), btScalar(0.0f), btScalar(0.0f));
}
btVector3 btConvexShape::localGetSupportVertexNonVirtual (const btVector3& localDir) const
@@ -388,7 +388,7 @@ btVector3 btConvexShape::localGetSupportVertexNonVirtual (const btVector3& local
case CONVEX_HULL_SHAPE_PROXYTYPE:
{
btConvexHullShape* convexHullShape = (btConvexHullShape*)this;
btPoint3* points = convexHullShape->getPoints ();
btVector3* points = convexHullShape->getPoints ();
int numPoints = convexHullShape->getNumPoints ();
return convexHullSupport (localDir, points, numPoints) + getMarginNonVirtual() * localDirNorm;
}
@@ -404,7 +404,7 @@ btVector3 btConvexShape::localGetSupportVertexNonVirtual (const btVector3& local
// should never reach here
btAssert (0);
return btPoint3 (btScalar(0.0f), btScalar(0.0f), btScalar(0.0f));
return btVector3 (btScalar(0.0f), btScalar(0.0f), btScalar(0.0f));
}
/* TODO: This should be bumped up to btCollisionShape () */
@@ -488,7 +488,7 @@ void btConvexShape::getAabbNonVirtual (const btTransform& t, btVector3& aabbMin,
btVector3 halfExtents = convexShape->getImplicitShapeDimensions();
halfExtents += btVector3(margin,margin,margin);
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
aabbMin = center - extent;
@@ -523,7 +523,7 @@ void btConvexShape::getAabbNonVirtual (const btTransform& t, btVector3& aabbMin,
halfExtents[m_upAxis] = capsuleShape->getRadius() + capsuleShape->getHalfHeight();
halfExtents += btVector3(capsuleShape->getMarginNonVirtual(),capsuleShape->getMarginNonVirtual(),capsuleShape->getMarginNonVirtual());
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
aabbMin = center - extent;
aabbMax = center + extent;

View File

@@ -163,12 +163,12 @@ int btConvexTriangleMeshShape::getNumEdges() const
return 0;
}
void btConvexTriangleMeshShape::getEdge(int ,btPoint3& ,btPoint3& ) const
void btConvexTriangleMeshShape::getEdge(int ,btVector3& ,btVector3& ) const
{
btAssert(0);
}
void btConvexTriangleMeshShape::getVertex(int ,btPoint3& ) const
void btConvexTriangleMeshShape::getVertex(int ,btVector3& ) const
{
btAssert(0);
}
@@ -178,13 +178,13 @@ int btConvexTriangleMeshShape::getNumPlanes() const
return 0;
}
void btConvexTriangleMeshShape::getPlane(btVector3& ,btPoint3& ,int ) const
void btConvexTriangleMeshShape::getPlane(btVector3& ,btVector3& ,int ) const
{
btAssert(0);
}
//not yet
bool btConvexTriangleMeshShape::isInside(const btPoint3& ,btScalar ) const
bool btConvexTriangleMeshShape::isInside(const btVector3& ,btScalar ) const
{
btAssert(0);
return false;

View File

@@ -34,11 +34,11 @@ public:
virtual int getNumVertices() const;
virtual int getNumEdges() const;
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const;
virtual void getVertex(int i,btPoint3& vtx) const;
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const;
virtual void getVertex(int i,btVector3& vtx) const;
virtual int getNumPlanes() const;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i ) const;
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const;
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i ) const;
virtual bool isInside(const btVector3& pt,btScalar tolerance) const;
virtual void setLocalScaling(const btVector3& scaling);

View File

@@ -13,7 +13,6 @@ subject to the following restrictions:
3. This notice may not be removed or altered from any source distribution.
*/
#include "btCylinderShape.h"
#include "LinearMath/btPoint3.h"
btCylinderShape::btCylinderShape (const btVector3& halfExtents)
:btBoxShape(halfExtents),

View File

@@ -95,7 +95,7 @@ void btHeightfieldTerrainShape::getAabb(const btTransform& t,btVector3& aabbMin,
halfExtents += btVector3(getMargin(),getMargin(),getMargin());
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),
abs_b[1].dot(halfExtents),
abs_b[2].dot(halfExtents));

View File

@@ -16,7 +16,6 @@ subject to the following restrictions:
#ifndef BU_SHAPE
#define BU_SHAPE
#include "LinearMath/btPoint3.h"
#include "LinearMath/btMatrix3x3.h"
#include "LinearMath/btAabbUtil2.h"
#include "btConvexInternalShape.h"
@@ -75,13 +74,13 @@ public:
virtual int getNumVertices() const = 0 ;
virtual int getNumEdges() const = 0;
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const = 0;
virtual void getVertex(int i,btPoint3& vtx) const = 0;
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const = 0;
virtual void getVertex(int i,btVector3& vtx) const = 0;
virtual int getNumPlanes() const = 0;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i ) const = 0;
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i ) const = 0;
// virtual int getIndex(int i) const = 0 ;
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const = 0;
virtual bool isInside(const btVector3& pt,btScalar tolerance) const = 0;
/// optional Hull is for optional Separating Axis Test Hull collision detection, see Hull.cpp
class Hull* m_optionalHull;

View File

@@ -93,7 +93,7 @@ void btScaledBvhTriangleMeshShape::getAabb(const btTransform& trans,btVector3& a
btMatrix3x3 abs_b = trans.getBasis().absolute();
btPoint3 center = trans(localCenter);
btVector3 center = trans(localCenter);
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
abs_b[1].dot(localHalfExtents),

View File

@@ -22,14 +22,14 @@ m_numVertices(0)
m_shapeType = TETRAHEDRAL_SHAPE_PROXYTYPE;
}
btBU_Simplex1to4::btBU_Simplex1to4(const btPoint3& pt0) : btPolyhedralConvexShape (),
btBU_Simplex1to4::btBU_Simplex1to4(const btVector3& pt0) : btPolyhedralConvexShape (),
m_numVertices(0)
{
m_shapeType = TETRAHEDRAL_SHAPE_PROXYTYPE;
addVertex(pt0);
}
btBU_Simplex1to4::btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1) : btPolyhedralConvexShape (),
btBU_Simplex1to4::btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1) : btPolyhedralConvexShape (),
m_numVertices(0)
{
m_shapeType = TETRAHEDRAL_SHAPE_PROXYTYPE;
@@ -37,7 +37,7 @@ m_numVertices(0)
addVertex(pt1);
}
btBU_Simplex1to4::btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1,const btPoint3& pt2) : btPolyhedralConvexShape (),
btBU_Simplex1to4::btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1,const btVector3& pt2) : btPolyhedralConvexShape (),
m_numVertices(0)
{
m_shapeType = TETRAHEDRAL_SHAPE_PROXYTYPE;
@@ -46,7 +46,7 @@ m_numVertices(0)
addVertex(pt2);
}
btBU_Simplex1to4::btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1,const btPoint3& pt2,const btPoint3& pt3) : btPolyhedralConvexShape (),
btBU_Simplex1to4::btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1,const btVector3& pt2,const btVector3& pt3) : btPolyhedralConvexShape (),
m_numVertices(0)
{
m_shapeType = TETRAHEDRAL_SHAPE_PROXYTYPE;
@@ -60,7 +60,7 @@ m_numVertices(0)
void btBU_Simplex1to4::addVertex(const btPoint3& pt)
void btBU_Simplex1to4::addVertex(const btVector3& pt)
{
m_vertices[m_numVertices++] = pt;
@@ -92,7 +92,7 @@ int btBU_Simplex1to4::getNumEdges() const
return 0;
}
void btBU_Simplex1to4::getEdge(int i,btPoint3& pa,btPoint3& pb) const
void btBU_Simplex1to4::getEdge(int i,btVector3& pa,btVector3& pb) const
{
switch (m_numVertices)
@@ -156,7 +156,7 @@ void btBU_Simplex1to4::getEdge(int i,btPoint3& pa,btPoint3& pb) const
}
void btBU_Simplex1to4::getVertex(int i,btPoint3& vtx) const
void btBU_Simplex1to4::getVertex(int i,btVector3& vtx) const
{
vtx = m_vertices[i];
}
@@ -183,7 +183,7 @@ int btBU_Simplex1to4::getNumPlanes() const
}
void btBU_Simplex1to4::getPlane(btVector3&, btPoint3& ,int ) const
void btBU_Simplex1to4::getPlane(btVector3&, btVector3& ,int ) const
{
}
@@ -193,7 +193,7 @@ int btBU_Simplex1to4::getIndex(int ) const
return 0;
}
bool btBU_Simplex1to4::isInside(const btPoint3& ,btScalar ) const
bool btBU_Simplex1to4::isInside(const btVector3& ,btScalar ) const
{
return false;
}

View File

@@ -27,15 +27,15 @@ class btBU_Simplex1to4 : public btPolyhedralConvexShape
protected:
int m_numVertices;
btPoint3 m_vertices[4];
btVector3 m_vertices[4];
public:
btBU_Simplex1to4();
btBU_Simplex1to4(const btPoint3& pt0);
btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1);
btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1,const btPoint3& pt2);
btBU_Simplex1to4(const btPoint3& pt0,const btPoint3& pt1,const btPoint3& pt2,const btPoint3& pt3);
btBU_Simplex1to4(const btVector3& pt0);
btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1);
btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1,const btVector3& pt2);
btBU_Simplex1to4(const btVector3& pt0,const btVector3& pt1,const btVector3& pt2,const btVector3& pt3);
void reset()
@@ -45,7 +45,7 @@ public:
void addVertex(const btPoint3& pt);
void addVertex(const btVector3& pt);
//PolyhedralConvexShape interface
@@ -53,17 +53,17 @@ public:
virtual int getNumEdges() const;
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const;
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const;
virtual void getVertex(int i,btPoint3& vtx) const;
virtual void getVertex(int i,btVector3& vtx) const;
virtual int getNumPlanes() const;
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i) const;
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i) const;
virtual int getIndex(int i) const;
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const;
virtual bool isInside(const btVector3& pt,btScalar tolerance) const;
///getName is for debugging

View File

@@ -53,7 +53,7 @@ void btTriangleMeshShape::getAabb(const btTransform& trans,btVector3& aabbMin,bt
btMatrix3x3 abs_b = trans.getBasis().absolute();
btPoint3 center = trans(localCenter);
btVector3 center = trans(localCenter);
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
abs_b[1].dot(localHalfExtents),

View File

@@ -46,7 +46,7 @@ public:
return 3;
}
virtual void getEdge(int i,btPoint3& pa,btPoint3& pb) const
virtual void getEdge(int i,btVector3& pa,btVector3& pb) const
{
getVertex(i,pa);
getVertex((i+1)%3,pb);
@@ -88,7 +88,7 @@ public:
}
virtual void getPlane(btVector3& planeNormal,btPoint3& planeSupport,int i) const
virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i) const
{
getPlaneEquation(i,planeNormal,planeSupport);
}
@@ -104,7 +104,7 @@ public:
normal.normalize();
}
virtual void getPlaneEquation(int i, btVector3& planeNormal,btPoint3& planeSupport) const
virtual void getPlaneEquation(int i, btVector3& planeNormal,btVector3& planeSupport) const
{
(void)i;
calcNormal(planeNormal);
@@ -118,7 +118,7 @@ public:
inertia.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
}
virtual bool isInside(const btPoint3& pt,btScalar tolerance) const
virtual bool isInside(const btVector3& pt,btScalar tolerance) const
{
btVector3 normal;
calcNormal(normal);
@@ -132,7 +132,7 @@ public:
int i;
for (i=0;i<3;i++)
{
btPoint3 pa,pb;
btVector3 pa,pb;
getEdge(i,pa,pb);
btVector3 edge = pb-pa;
btVector3 edgeNormal = edge.cross(normal);

View File

@@ -21,7 +21,6 @@ class btStackAlloc;
class btVector3;
#include "btSimplexSolverInterface.h"
class btConvexShape;
#include "LinearMath/btPoint3.h"
class btTransform;
///ConvexPenetrationDepthSolver provides an interface for penetration depth calculation.
@@ -33,7 +32,7 @@ public:
virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver,
const btConvexShape* convexA,const btConvexShape* convexB,
const btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc
) = 0;

View File

@@ -31,7 +31,7 @@ subject to the following restrictions:
bool btGjkEpaPenetrationDepthSolver::calcPenDepth( btSimplexSolverInterface& simplexSolver,
const btConvexShape* pConvexA, const btConvexShape* pConvexB,
const btTransform& transformA, const btTransform& transformB,
btVector3& v, btPoint3& wWitnessOnA, btPoint3& wWitnessOnB,
btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB,
class btIDebugDraw* debugDraw, btStackAlloc* stackAlloc )
{

View File

@@ -28,7 +28,7 @@ class btGjkEpaPenetrationDepthSolver : public btConvexPenetrationDepthSolver
bool calcPenDepth( btSimplexSolverInterface& simplexSolver,
const btConvexShape* pConvexA, const btConvexShape* pConvexB,
const btTransform& transformA, const btTransform& transformB,
btVector3& v, btPoint3& wWitnessOnA, btPoint3& wWitnessOnB,
btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc );
private :

View File

@@ -130,8 +130,8 @@ void btGjkPairDetector::getClosestPoints(const ClosestPointInput& input,Result&
btAssert((qInBv-qInB).length() < 0.0001);
#endif //
btPoint3 pWorld = localTransA(pInA);
btPoint3 qWorld = localTransB(qInB);
btVector3 pWorld = localTransA(pInA);
btVector3 qWorld = localTransB(qInB);
#ifdef DEBUG_SPU_COLLISION_DETECTION
spu_printf("got local supporting vertices\n");

View File

@@ -20,7 +20,6 @@ subject to the following restrictions:
#define GJK_PAIR_DETECTOR_H
#include "btDiscreteCollisionDetectorInterface.h"
#include "LinearMath/btPoint3.h"
#include "BulletCollision/CollisionShapes/btCollisionMargin.h"
class btConvexShape;

View File

@@ -70,7 +70,7 @@ btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& simplexSolver,
const btConvexShape* convexA,const btConvexShape* convexB,
const btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc
)
{

View File

@@ -27,7 +27,7 @@ public:
virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver,
const btConvexShape* convexA,const btConvexShape* convexB,
const btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc
);
};

View File

@@ -19,7 +19,6 @@ subject to the following restrictions:
#define SIMPLEX_SOLVER_INTERFACE_H
#include "LinearMath/btVector3.h"
#include "LinearMath/btPoint3.h"
#define NO_VIRTUAL_INTERFACE 1
#ifdef NO_VIRTUAL_INTERFACE
@@ -37,7 +36,7 @@ class btSimplexSolverInterface
virtual void reset() = 0;
virtual void addVertex(const btVector3& w, const btPoint3& p, const btPoint3& q) = 0;
virtual void addVertex(const btVector3& w, const btVector3& p, const btVector3& q) = 0;
virtual bool closest(btVector3& v) = 0;
@@ -45,7 +44,7 @@ class btSimplexSolverInterface
virtual bool fullSimplex() const = 0;
virtual int getSimplex(btPoint3 *pBuf, btPoint3 *qBuf, btVector3 *yBuf) const = 0;
virtual int getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const = 0;
virtual bool inSimplex(const btVector3& w) = 0;
@@ -53,7 +52,7 @@ class btSimplexSolverInterface
virtual bool emptySimplex() const = 0;
virtual void compute_points(btPoint3& p1, btPoint3& p2) = 0;
virtual void compute_points(btVector3& p1, btVector3& p2) = 0;
virtual int numVertices() const =0;

View File

@@ -77,7 +77,7 @@ void btVoronoiSimplexSolver::reset()
//add a vertex
void btVoronoiSimplexSolver::addVertex(const btVector3& w, const btPoint3& p, const btPoint3& q)
void btVoronoiSimplexSolver::addVertex(const btVector3& w, const btVector3& p, const btVector3& q)
{
m_lastW = w;
m_needsUpdate = true;
@@ -267,7 +267,7 @@ btScalar btVoronoiSimplexSolver::maxVertex()
//return the current simplex
int btVoronoiSimplexSolver::getSimplex(btPoint3 *pBuf, btPoint3 *qBuf, btVector3 *yBuf) const
int btVoronoiSimplexSolver::getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const
{
int i;
for (i=0;i<numVertices();i++)
@@ -314,7 +314,7 @@ bool btVoronoiSimplexSolver::emptySimplex() const
}
void btVoronoiSimplexSolver::compute_points(btPoint3& p1, btPoint3& p2)
void btVoronoiSimplexSolver::compute_points(btVector3& p1, btVector3& p2)
{
updateClosestVectorAndPoints();
p1 = m_cachedP1;
@@ -325,7 +325,7 @@ void btVoronoiSimplexSolver::compute_points(btPoint3& p1, btPoint3& p2)
bool btVoronoiSimplexSolver::closestPtPointTriangle(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c,btSubSimplexClosestResult& result)
bool btVoronoiSimplexSolver::closestPtPointTriangle(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c,btSubSimplexClosestResult& result)
{
result.m_usedVertices.reset();
@@ -425,7 +425,7 @@ bool btVoronoiSimplexSolver::closestPtPointTriangle(const btPoint3& p, const btP
/// Test if point p and d lie on opposite sides of plane through abc
int btVoronoiSimplexSolver::pointOutsideOfPlane(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d)
int btVoronoiSimplexSolver::pointOutsideOfPlane(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d)
{
btVector3 normal = (b-a).cross(c-a);
@@ -452,7 +452,7 @@ if (signd * signd < (btScalar(1e-8) * btScalar(1e-8)))
}
bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d, btSubSimplexClosestResult& finalResult)
bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d, btSubSimplexClosestResult& finalResult)
{
btSubSimplexClosestResult tempResult;
@@ -486,7 +486,7 @@ bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideABC)
{
closestPtPointTriangle(p, a, b, c,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
btScalar sqDist = (q - p).dot( q - p);
// Update best closest point if (squared) distance is less than current best
@@ -513,7 +513,7 @@ bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideACD)
{
closestPtPointTriangle(p, a, c, d,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
@@ -541,7 +541,7 @@ bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideADB)
{
closestPtPointTriangle(p, a, d, b,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
@@ -569,7 +569,7 @@ bool btVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideBDC)
{
closestPtPointTriangle(p, b, d, c,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
if (sqDist < bestSqDist)

View File

@@ -50,7 +50,7 @@ struct btUsageBitfield{
struct btSubSimplexClosestResult
{
btPoint3 m_closestPointOnSimplex;
btVector3 m_closestPointOnSimplex;
//MASK for m_usedVertices
//stores the simplex vertex-usage, using the MASK,
// if m_usedVertices & MASK then the related vertex is used
@@ -97,13 +97,13 @@ public:
int m_numVertices;
btVector3 m_simplexVectorW[VORONOI_SIMPLEX_MAX_VERTS];
btPoint3 m_simplexPointsP[VORONOI_SIMPLEX_MAX_VERTS];
btPoint3 m_simplexPointsQ[VORONOI_SIMPLEX_MAX_VERTS];
btVector3 m_simplexPointsP[VORONOI_SIMPLEX_MAX_VERTS];
btVector3 m_simplexPointsQ[VORONOI_SIMPLEX_MAX_VERTS];
btPoint3 m_cachedP1;
btPoint3 m_cachedP2;
btVector3 m_cachedP1;
btVector3 m_cachedP2;
btVector3 m_cachedV;
btVector3 m_lastW;
bool m_cachedValidClosest;
@@ -116,15 +116,15 @@ public:
void reduceVertices (const btUsageBitfield& usedVerts);
bool updateClosestVectorAndPoints();
bool closestPtPointTetrahedron(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d, btSubSimplexClosestResult& finalResult);
int pointOutsideOfPlane(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d);
bool closestPtPointTriangle(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c,btSubSimplexClosestResult& result);
bool closestPtPointTetrahedron(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d, btSubSimplexClosestResult& finalResult);
int pointOutsideOfPlane(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d);
bool closestPtPointTriangle(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c,btSubSimplexClosestResult& result);
public:
void reset();
void addVertex(const btVector3& w, const btPoint3& p, const btPoint3& q);
void addVertex(const btVector3& w, const btVector3& p, const btVector3& q);
bool closest(btVector3& v);
@@ -136,7 +136,7 @@ public:
return (m_numVertices == 4);
}
int getSimplex(btPoint3 *pBuf, btPoint3 *qBuf, btVector3 *yBuf) const;
int getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const;
bool inSimplex(const btVector3& w);
@@ -144,7 +144,7 @@ public:
bool emptySimplex() const ;
void compute_points(btPoint3& p1, btPoint3& p2) ;
void compute_points(btVector3& p1, btVector3& p2) ;
int numVertices() const
{

View File

@@ -255,7 +255,7 @@ void plAddVertex(plCollisionShapeHandle cshape, plReal x,plReal y,plReal z)
(void)colShape;
btAssert(colShape->getShapeType()==CONVEX_HULL_SHAPE_PROXYTYPE);
btConvexHullShape* convexHullShape = reinterpret_cast<btConvexHullShape*>( cshape);
convexHullShape->addPoint(btPoint3(x,y,z));
convexHullShape->addPoint(btVector3(x,y,z));
}

View File

@@ -180,7 +180,7 @@ void btDiscreteDynamicsWorld::debugDrawWorld()
}
if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
{
btPoint3 minAabb,maxAabb;
btVector3 minAabb,maxAabb;
btVector3 colorvec(1,0,0);
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
m_debugDrawer->drawAabb(minAabb,maxAabb,colorvec);
@@ -1135,7 +1135,7 @@ void btDiscreteDynamicsWorld::debugDrawObject(const btTransform& worldTransform,
int i;
for (i=0;i<polyshape->getNumEdges();i++)
{
btPoint3 a,b;
btVector3 a,b;
polyshape->getEdge(i,a,b);
btVector3 wa = worldTransform * a;
btVector3 wb = worldTransform * b;

View File

@@ -17,7 +17,6 @@ subject to the following restrictions:
#define RIGIDBODY_H
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btPoint3.h"
#include "LinearMath/btTransform.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
@@ -303,7 +302,7 @@ public:
void updateInertiaTensor();
const btPoint3& getCenterOfMassPosition() const {
const btVector3& getCenterOfMassPosition() const {
return m_worldTransform.getOrigin();
}
btQuaternion getOrientation() const;
@@ -353,7 +352,7 @@ public:
SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const btPoint3& pos, const btVector3& normal) const
SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const btVector3& pos, const btVector3& normal) const
{
btVector3 r0 = pos - getCenterOfMassPosition();

View File

@@ -156,7 +156,7 @@ void btSimpleDynamicsWorld::updateAabbs()
{
if (body->isActive() && (!body->isStaticObject()))
{
btPoint3 minAabb,maxAabb;
btVector3 minAabb,maxAabb;
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
btBroadphaseInterface* bp = getBroadphase();
bp->setAabb(body->getBroadphaseHandle(),minAabb,maxAabb, m_dispatcher1);

View File

@@ -16,13 +16,13 @@ subject to the following restrictions:
#include "SpuCollisionShapes.h"
btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const btVector3& localDir,struct SpuConvexPolyhedronVertexData* convexVertexData)//, int *featureIndex)
btVector3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const btVector3& localDir,struct SpuConvexPolyhedronVertexData* convexVertexData)//, int *featureIndex)
{
switch (shapeType)
{
case SPHERE_SHAPE_PROXYTYPE:
{
return btPoint3(0,0,0);
return btVector3(0,0,0);
}
case BOX_SHAPE_PROXYTYPE:
{
@@ -30,7 +30,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
btConvexInternalShape* convexShape = (btConvexInternalShape*)shape;
const btVector3& halfExtents = convexShape->getImplicitShapeDimensions();
return btPoint3(
return btVector3(
localDir.getX() < 0.0f ? -halfExtents.x() : halfExtents.x(),
localDir.getY() < 0.0f ? -halfExtents.y() : halfExtents.y(),
localDir.getZ() < 0.0f ? -halfExtents.z() : halfExtents.z());
@@ -43,7 +43,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
btVector3* vertices = (btVector3*)shape;
btVector3 dots(dir.dot(vertices[0]), dir.dot(vertices[1]), dir.dot(vertices[2]));
btVector3 sup = vertices[dots.maxAxis()];
return btPoint3(sup.getX(),sup.getY(),sup.getZ());
return btVector3(sup.getX(),sup.getY(),sup.getZ());
break;
}
@@ -100,14 +100,14 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
tmp[XX] = v[XX] * d;
tmp[YY] = v[YY] < 0.0 ? -halfHeight : halfHeight;
tmp[ZZ] = v[ZZ] * d;
return btPoint3(tmp.getX(),tmp.getY(),tmp.getZ());
return btVector3(tmp.getX(),tmp.getY(),tmp.getZ());
}
else
{
tmp[XX] = radius;
tmp[YY] = v[YY] < 0.0 ? -halfHeight : halfHeight;
tmp[ZZ] = btScalar(0.0);
return btPoint3(tmp.getX(),tmp.getY(),tmp.getZ());
return btVector3(tmp.getX(),tmp.getY(),tmp.getZ());
}
}
@@ -162,7 +162,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
supVec = vtx;
}
}
return btPoint3(supVec.getX(),supVec.getY(),supVec.getZ());
return btVector3(supVec.getX(),supVec.getY(),supVec.getZ());
break;
};
@@ -172,7 +172,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
btPoint3* points = 0;
btVector3* points = 0;
int numPoints = 0;
points = convexVertexData->gConvexPoints;
numPoints = convexVertexData->gNumConvexPoints;
@@ -197,7 +197,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
for (int i=0;i<numPoints;i++)
{
btPoint3 vtx = points[i];// * m_localScaling;
btVector3 vtx = points[i];// * m_localScaling;
newDot = vec.dot(vtx);
if (newDot > maxDot)
@@ -206,7 +206,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
supVec = vtx;
}
}
return btPoint3(supVec.getX(),supVec.getY(),supVec.getZ());
return btVector3(supVec.getX(),supVec.getY(),supVec.getZ());
break;
};
@@ -219,7 +219,7 @@ btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const
#if __ASSERT
// spu_printf("localGetSupportingVertexWithoutMargin() - Unsupported bound type: %d.\n", shapeType);
#endif // __ASSERT
return btPoint3(0.f, 0.f, 0.f);
return btVector3(0.f, 0.f, 0.f);
}
}
@@ -237,7 +237,7 @@ void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape*
halfExtents += btVector3(margin,margin,margin);
btTransform& t = xform;
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
aabbMin = center - extent;
@@ -260,7 +260,7 @@ void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape*
#endif
btTransform& t = xform;
btMatrix3x3 abs_b = t.getBasis().absolute();
btPoint3 center = t.getOrigin();
btVector3 center = t.getOrigin();
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
aabbMin = center - extent;
@@ -410,7 +410,7 @@ void dmaConvexVertexData (SpuConvexPolyhedronVertexData* convexVertexData, btCon
return;
}
register int dmaSize = convexVertexData->gNumConvexPoints*sizeof(btPoint3);
register int dmaSize = convexVertexData->gNumConvexPoints*sizeof(btVector3);
ppu_address_t pointsPPU = (ppu_address_t) convexShapeSPU->getPoints();
cellDmaGet(&convexVertexData->g_convexPointBuffer[0], pointsPPU , dmaSize, DMA_TAG(2), 0, 0);
}

View File

@@ -23,9 +23,9 @@
struct SpuConvexPolyhedronVertexData
{
void* gSpuConvexShapePtr;
btPoint3* gConvexPoints;
btVector3* gConvexPoints;
int gNumConvexPoints;
ATTRIBUTE_ALIGNED16(btPoint3 g_convexPointBuffer[MAX_NUM_SPU_CONVEX_POINTS]);
ATTRIBUTE_ALIGNED16(btVector3 g_convexPointBuffer[MAX_NUM_SPU_CONVEX_POINTS]);
};
#define MAX_SHAPE_SIZE 256
@@ -63,7 +63,7 @@ struct bvhMeshShape_LocalStoreMemory
};
btPoint3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const btVector3& localDir,struct SpuConvexPolyhedronVertexData* convexVertexData);//, int *featureIndex)
btVector3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const btVector3& localDir,struct SpuConvexPolyhedronVertexData* convexVertexData);//, int *featureIndex)
void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape* convexShape, ppu_address_t convexShapePtr, int shapeType, btTransform xform);
void dmaBvhShapeData (bvhMeshShape_LocalStoreMemory* bvhMeshShape, btBvhTriangleMeshShape* triMeshShape);
void dmaBvhIndexedMesh (btIndexedMesh* IndexMesh, IndexedMeshArray& indexArray, int index, uint32_t dmaTag);

View File

@@ -170,7 +170,7 @@ void SpuContactResult::writeDoubleBufferedManifold(btPersistentManifold* lsManif
//no, the swapBuffers does the wait
}
void SpuContactResult::addContactPoint(const btVector3& normalOnBInWorld,const btPoint3& pointInWorld,float depth)
void SpuContactResult::addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,float depth)
{
//spu_printf("*** SpuContactResult::addContactPoint: depth = %f\n",depth);

View File

@@ -27,7 +27,6 @@ subject to the following restrictions:
#include "LinearMath/btTransform.h"
#include "LinearMath/btPoint3.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
@@ -102,7 +101,7 @@ class SpuContactResult
void writeDoubleBufferedManifold(btPersistentManifold* lsManifold, btPersistentManifold* mmManifold);
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btPoint3& pointInWorld,float depth);
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,float depth);
void flush();
};

View File

@@ -25,7 +25,6 @@ class btIDebugDraw;
class SpuVoronoiSimplexSolver;
#include <LinearMath/btTransform.h>
#include <LinearMath/btPoint3.h>
///ConvexPenetrationDepthSolver provides an interface for penetration depth calculation.
@@ -37,7 +36,7 @@ public:
virtual bool calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver,
void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB,
btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc,
struct SpuConvexPolyhedronVertexData* convexVertexDataA,
struct SpuConvexPolyhedronVertexData* convexVertexDataB

View File

@@ -22,7 +22,7 @@ subject to the following restrictions:
bool SpuEpaPenetrationDepthSolver::calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver,
void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB,
btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc,
struct SpuConvexPolyhedronVertexData* convexVertexDataA,
struct SpuConvexPolyhedronVertexData* convexVertexDataB

View File

@@ -33,7 +33,7 @@ public:
virtual bool calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver,
void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB,
btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc,
struct SpuConvexPolyhedronVertexData* convexVertexDataA,
struct SpuConvexPolyhedronVertexData* convexVertexDataB

View File

@@ -110,8 +110,8 @@ void SpuGjkPairDetector::getClosestPoints(const SpuClosestPointInput& input,SpuC
btVector3 qInB = localGetSupportingVertexWithoutMargin(m_shapeTypeB, m_minkowskiB, seperatingAxisInB,input.m_convexVertexData[1]);//, &featureIndexB);
btPoint3 pWorld = localTransA(pInA);
btPoint3 qWorld = localTransB(qInB);
btVector3 pWorld = localTransA(pInA);
btVector3 qWorld = localTransB(qInB);
btVector3 w = pWorld - qWorld;
delta = m_cachedSeparatingAxis.dot(w);

View File

@@ -72,7 +72,7 @@ btVector3(btScalar(0.162456) , btScalar(0.499995),btScalar(0.850654))
bool SpuMinkowskiPenetrationDepthSolver::calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver,
void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB,
btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc,
struct SpuConvexPolyhedronVertexData* convexVertexDataA,
struct SpuConvexPolyhedronVertexData* convexVertexDataB

View File

@@ -33,7 +33,7 @@ public:
virtual bool calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver,
void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB,
btTransform& transA,const btTransform& transB,
btVector3& v, btPoint3& pa, btPoint3& pb,
btVector3& v, btVector3& pa, btVector3& pb,
class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc,
struct SpuConvexPolyhedronVertexData* convexVertexDataA,
struct SpuConvexPolyhedronVertexData* convexVertexDataB

View File

@@ -77,7 +77,7 @@ void SpuVoronoiSimplexSolver::reset()
//add a vertex
void SpuVoronoiSimplexSolver::addVertex(const btVector3& w, const btPoint3& p, const btPoint3& q)
void SpuVoronoiSimplexSolver::addVertex(const btVector3& w, const btVector3& p, const btVector3& q)
{
m_lastW = w;
m_needsUpdate = true;
@@ -269,7 +269,7 @@ btScalar SpuVoronoiSimplexSolver::maxVertex()
//return the current simplex
int SpuVoronoiSimplexSolver::getSimplex(btPoint3 *pBuf, btPoint3 *qBuf, btVector3 *yBuf) const
int SpuVoronoiSimplexSolver::getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const
{
int i;
for (i=0;i<numVertices();i++)
@@ -316,7 +316,7 @@ bool SpuVoronoiSimplexSolver::emptySimplex() const
}
void SpuVoronoiSimplexSolver::compute_points(btPoint3& p1, btPoint3& p2)
void SpuVoronoiSimplexSolver::compute_points(btVector3& p1, btVector3& p2)
{
updateClosestVectorAndPoints();
p1 = m_cachedP1;
@@ -327,7 +327,7 @@ void SpuVoronoiSimplexSolver::compute_points(btPoint3& p1, btPoint3& p2)
bool SpuVoronoiSimplexSolver::closestPtPointTriangle(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c,SpuSubSimplexClosestResult& result)
bool SpuVoronoiSimplexSolver::closestPtPointTriangle(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c,SpuSubSimplexClosestResult& result)
{
result.m_usedVertices.reset();
@@ -427,7 +427,7 @@ bool SpuVoronoiSimplexSolver::closestPtPointTriangle(const btPoint3& p, const bt
/// Test if point p and d lie on opposite sides of plane through abc
int SpuVoronoiSimplexSolver::pointOutsideOfPlane(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d)
int SpuVoronoiSimplexSolver::pointOutsideOfPlane(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d)
{
btVector3 normal = (b-a).cross(c-a);
@@ -454,7 +454,7 @@ if (signd * signd < (btScalar(1e-8) * btScalar(1e-8)))
}
bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const btPoint3& a, const btPoint3& b, const btPoint3& c, const btPoint3& d, SpuSubSimplexClosestResult& finalResult)
bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d, SpuSubSimplexClosestResult& finalResult)
{
SpuSubSimplexClosestResult tempResult;
@@ -488,7 +488,7 @@ bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideABC)
{
closestPtPointTriangle(p, a, b, c,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
btScalar sqDist = (q - p).dot( q - p);
// Update best closest point if (squared) distance is less than current best
@@ -515,7 +515,7 @@ bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideACD)
{
closestPtPointTriangle(p, a, c, d,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
@@ -542,7 +542,7 @@ bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideADB)
{
closestPtPointTriangle(p, a, d, b,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
@@ -569,7 +569,7 @@ bool SpuVoronoiSimplexSolver::closestPtPointTetrahedron(const btPoint3& p, const
if (pointOutsideBDC)
{
closestPtPointTriangle(p, b, d, c,tempResult);
btPoint3 q = tempResult.m_closestPointOnSimplex;
btVector3 q = tempResult.m_closestPointOnSimplex;
//convert result bitmask!
btScalar sqDist = (q - p).dot( q - p);
if (sqDist < bestSqDist)

View File

@@ -19,8 +19,7 @@ subject to the following restrictions:
#ifndef SPUVoronoiSimplexSolver_H
#define SPUVoronoiSimplexSolver_H
#include <LinearMath/btTransform.h>
#include <LinearMath/btPoint3.h>
#include "LinearMath/btTransform.h"
#define VORONOI_SIMPLEX_MAX_VERTS 5
@@ -123,7 +122,7 @@ public:
void reset();
void addVertex(const btVector3& w, const btPoint3& p, const btPoint3& q);
void addVertex(const btVector3& w, const btVector3& p, const btVector3& q);
bool closest(btVector3& v);

View File

@@ -18,7 +18,6 @@ subject to the following restrictions:
#define _BT_SOFT_BODY_H
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btPoint3.h"
#include "LinearMath/btTransform.h"
#include "LinearMath/btIDebugDraw.h"
#include "BulletDynamics/Dynamics/btRigidBody.h"
@@ -417,7 +416,7 @@ public:
struct eType { enum _ {
Linear,
Angular,
Contact,
Contact
};};
struct Specs
{

View File

@@ -39,7 +39,7 @@ struct fDrawFlags { enum _ {
Joints = 0x1000,
/* presets */
Std = Links+Faces+Tetras+Anchors+Notes+Joints,
StdTetra = Std-Faces+Tetras,
StdTetra = Std-Faces+Tetras
};};
struct btSoftBodyHelpers

View File

@@ -25,7 +25,6 @@ ADD_LIBRARY(LibLinearMath
btTransform.h
btAlignedAllocator.h
btIDebugDraw.h
btPoint3.h
btQuickprof.h
btTransformUtil.h
btQuickprof.cpp

View File

@@ -1,24 +0,0 @@
/*
Copyright (c) 2003-2006 Gino van den Bergen / 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.
*/
#ifndef btPoint3_H
#define btPoint3_H
#include "btVector3.h"
typedef btVector3 btPoint3;
#endif

View File

@@ -21,7 +21,6 @@ libbulletmath_a_SOURCES = \
LinearMath/btAlignedAllocator.h \
LinearMath/btQuaternion.h \
LinearMath/btAlignedObjectArray.h \
LinearMath/btPoint3.h \
LinearMath/btQuickprof.h \
LinearMath/btTransformUtil.h \
LinearMath/btTransform.h \