First stage in refactoring Bullet: moved Bullet Collision and Dynamics and LinearMath into src folder, and all files in Collision Detection and Dynamics have bt prefix.
Made all buildsystems to work again (jam, msvc, cmake)
This commit is contained in:
@@ -1,59 +0,0 @@
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet }
|
||||
)
|
||||
|
||||
ADD_LIBRARY(LibBulletCollision
|
||||
BroadphaseCollision/AxisSweep3.cpp
|
||||
BroadphaseCollision/BroadphaseProxy.cpp
|
||||
BroadphaseCollision/CollisionAlgorithm.cpp
|
||||
BroadphaseCollision/Dispatcher.cpp
|
||||
BroadphaseCollision/OverlappingPairCache.cpp
|
||||
BroadphaseCollision/SimpleBroadphase.cpp
|
||||
CollisionDispatch/CollisionDispatcher.cpp
|
||||
CollisionDispatch/CollisionObject.cpp
|
||||
CollisionDispatch/CollisionWorld.cpp
|
||||
CollisionDispatch/CompoundCollisionAlgorithm.cpp
|
||||
CollisionDispatch/ConvexConcaveCollisionAlgorithm.cpp
|
||||
CollisionDispatch/SphereSphereCollisionAlgorithm.cpp
|
||||
CollisionDispatch/ConvexConvexAlgorithm.cpp
|
||||
CollisionDispatch/EmptyCollisionAlgorithm.cpp
|
||||
CollisionDispatch/ManifoldResult.cpp
|
||||
CollisionDispatch/SimulationIslandManager.cpp
|
||||
CollisionDispatch/UnionFind.cpp
|
||||
CollisionShapes/BoxShape.cpp
|
||||
CollisionShapes/BvhTriangleMeshShape.cpp
|
||||
CollisionShapes/CollisionShape.cpp
|
||||
CollisionShapes/CompoundShape.cpp
|
||||
CollisionShapes/ConcaveShape.cpp
|
||||
CollisionShapes/ConeShape.cpp
|
||||
CollisionShapes/ConvexHullShape.cpp
|
||||
CollisionShapes/ConvexShape.cpp
|
||||
CollisionShapes/ConvexTriangleMeshShape.cpp
|
||||
CollisionShapes/CylinderShape.cpp
|
||||
CollisionShapes/EmptyShape.cpp
|
||||
CollisionShapes/MinkowskiSumShape.cpp
|
||||
CollisionShapes/MultiSphereShape.cpp
|
||||
CollisionShapes/OptimizedBvh.cpp
|
||||
CollisionShapes/PolyhedralConvexShape.cpp
|
||||
CollisionShapes/Simplex1to4Shape.cpp
|
||||
CollisionShapes/SphereShape.cpp
|
||||
CollisionShapes/StaticPlaneShape.cpp
|
||||
CollisionShapes/StridingMeshInterface.cpp
|
||||
CollisionShapes/TriangleCallback.cpp
|
||||
CollisionShapes/TriangleIndexVertexArray.cpp
|
||||
CollisionShapes/TriangleMesh.cpp
|
||||
CollisionShapes/TriangleMeshShape.cpp
|
||||
NarrowPhaseCollision/ContinuousConvexCollision.cpp
|
||||
NarrowPhaseCollision/ConvexCast.cpp
|
||||
NarrowPhaseCollision/GjkConvexCast.cpp
|
||||
NarrowPhaseCollision/GjkPairDetector.cpp
|
||||
NarrowPhaseCollision/Hull.cpp
|
||||
NarrowPhaseCollision/ManifoldContactAddResult.cpp
|
||||
NarrowPhaseCollision/MinkowskiPenetrationDepthSolver.cpp
|
||||
NarrowPhaseCollision/PersistentManifold.cpp
|
||||
NarrowPhaseCollision/RaycastCallback.cpp
|
||||
NarrowPhaseCollision/Shape.cpp
|
||||
NarrowPhaseCollision/SubSimplexConvexCast.cpp
|
||||
NarrowPhaseCollision/VoronoiSimplexSolver.cpp
|
||||
)
|
||||
@@ -1,26 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef COLLISION_MARGIN_H
|
||||
#define COLLISION_MARGIN_H
|
||||
|
||||
//used by Gjk and some other algorithms
|
||||
|
||||
#define CONVEX_DISTANCE_MARGIN 0.04f// 0.1f//;//0.01f
|
||||
|
||||
|
||||
|
||||
#endif //COLLISION_MARGIN_H
|
||||
|
||||
@@ -1,19 +0,0 @@
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics }
|
||||
)
|
||||
|
||||
ADD_LIBRARY(LibBulletDynamics
|
||||
|
||||
ConstraintSolver/ContactConstraint.cpp
|
||||
ConstraintSolver/Generic6DofConstraint.cpp
|
||||
ConstraintSolver/HingeConstraint.cpp
|
||||
ConstraintSolver/Point2PointConstraint.cpp
|
||||
ConstraintSolver/SequentialImpulseConstraintSolver.cpp
|
||||
ConstraintSolver/Solve2LinearConstraint.cpp
|
||||
ConstraintSolver/TypedConstraint.cpp
|
||||
Dynamics/BU_Joint.cpp
|
||||
Dynamics/ContactJoint.cpp
|
||||
Dynamics/RigidBody.cpp
|
||||
Vehicle/RaycastVehicle.cpp
|
||||
Vehicle/WheelInfo.cpp
|
||||
)
|
||||
@@ -1,25 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#include "BU_Joint.h"
|
||||
|
||||
BU_Joint::BU_Joint()
|
||||
{
|
||||
|
||||
}
|
||||
BU_Joint::~BU_Joint()
|
||||
{
|
||||
|
||||
}
|
||||
@@ -1,93 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef BU_Joint_H
|
||||
#define BU_Joint_H
|
||||
|
||||
class RigidBody;
|
||||
class BU_Joint;
|
||||
#include "SimdScalar.h"
|
||||
|
||||
struct BU_ContactJointNode {
|
||||
BU_Joint *joint; // pointer to enclosing BU_Joint object
|
||||
RigidBody*body; // *other* body this joint is connected to
|
||||
};
|
||||
typedef SimdScalar dVector3[4];
|
||||
|
||||
|
||||
class BU_Joint {
|
||||
|
||||
public:
|
||||
// naming convention: the "first" body this is connected to is node[0].body,
|
||||
// and the "second" body is node[1].body. if this joint is only connected
|
||||
// to one body then the second body is 0.
|
||||
|
||||
// info returned by getInfo1 function. the constraint dimension is m (<=6).
|
||||
// i.e. that is the total number of rows in the jacobian. `nub' is the
|
||||
// number of unbounded variables (which have lo,hi = -/+ infinity).
|
||||
|
||||
BU_Joint();
|
||||
virtual ~BU_Joint();
|
||||
|
||||
|
||||
struct Info1 {
|
||||
int m,nub;
|
||||
};
|
||||
|
||||
// info returned by getInfo2 function
|
||||
|
||||
struct Info2 {
|
||||
// integrator parameters: frames per second (1/stepsize), default error
|
||||
// reduction parameter (0..1).
|
||||
SimdScalar fps,erp;
|
||||
|
||||
// for the first and second body, pointers to two (linear and angular)
|
||||
// n*3 jacobian sub matrices, stored by rows. these matrices will have
|
||||
// been initialized to 0 on entry. if the second body is zero then the
|
||||
// J2xx pointers may be 0.
|
||||
SimdScalar *J1l,*J1a,*J2l,*J2a;
|
||||
|
||||
// elements to jump from one row to the next in J's
|
||||
int rowskip;
|
||||
|
||||
// right hand sides of the equation J*v = c + cfm * lambda. cfm is the
|
||||
// "constraint force mixing" vector. c is set to zero on entry, cfm is
|
||||
// set to a constant value (typically very small or zero) value on entry.
|
||||
SimdScalar *c,*cfm;
|
||||
|
||||
// lo and hi limits for variables (set to -/+ infinity on entry).
|
||||
SimdScalar *lo,*hi;
|
||||
|
||||
// findex vector for variables. see the LCP solver interface for a
|
||||
// description of what this does. this is set to -1 on entry.
|
||||
// note that the returned indexes are relative to the first index of
|
||||
// the constraint.
|
||||
int *findex;
|
||||
};
|
||||
|
||||
// virtual function table: size of the joint structure, function pointers.
|
||||
// we do it this way instead of using C++ virtual functions because
|
||||
// sometimes we need to allocate joints ourself within a memory pool.
|
||||
|
||||
virtual void GetInfo1 (Info1 *info)=0;
|
||||
virtual void GetInfo2 (Info2 *info)=0;
|
||||
|
||||
int flags; // dJOINT_xxx flags
|
||||
BU_ContactJointNode node[2]; // connections to bodies. node[1].body can be 0
|
||||
SimdScalar lambda[6]; // lambda generated by last step
|
||||
};
|
||||
|
||||
|
||||
#endif //BU_Joint_H
|
||||
@@ -1,270 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
#include "ContactJoint.h"
|
||||
#include "RigidBody.h"
|
||||
#include "NarrowPhaseCollision/PersistentManifold.h"
|
||||
|
||||
|
||||
//this constant needs to be set up so different solvers give 'similar' results
|
||||
#define FRICTION_CONSTANT 120.f
|
||||
|
||||
|
||||
ContactJoint::ContactJoint(PersistentManifold* manifold,int index,bool swap,RigidBody* body0,RigidBody* body1)
|
||||
:m_manifold(manifold),
|
||||
m_index(index),
|
||||
m_swapBodies(swap),
|
||||
m_body0(body0),
|
||||
m_body1(body1)
|
||||
{
|
||||
}
|
||||
|
||||
int m_numRows = 3;
|
||||
|
||||
|
||||
void ContactJoint::GetInfo1(Info1 *info)
|
||||
{
|
||||
info->m = m_numRows;
|
||||
//friction adds another 2...
|
||||
|
||||
info->nub = 0;
|
||||
}
|
||||
|
||||
#define dCROSS(a,op,b,c) \
|
||||
(a)[0] op ((b)[1]*(c)[2] - (b)[2]*(c)[1]); \
|
||||
(a)[1] op ((b)[2]*(c)[0] - (b)[0]*(c)[2]); \
|
||||
(a)[2] op ((b)[0]*(c)[1] - (b)[1]*(c)[0]);
|
||||
|
||||
#define M_SQRT12 SimdScalar(0.7071067811865475244008443621048490)
|
||||
|
||||
#define dRecipSqrt(x) ((float)(1.0f/SimdSqrt(float(x)))) /* reciprocal square root */
|
||||
|
||||
|
||||
|
||||
void dPlaneSpace1 (const dVector3 n, dVector3 p, dVector3 q)
|
||||
{
|
||||
if (SimdFabs(n[2]) > M_SQRT12) {
|
||||
// choose p in y-z plane
|
||||
SimdScalar a = n[1]*n[1] + n[2]*n[2];
|
||||
SimdScalar k = dRecipSqrt (a);
|
||||
p[0] = 0;
|
||||
p[1] = -n[2]*k;
|
||||
p[2] = n[1]*k;
|
||||
// set q = n x p
|
||||
q[0] = a*k;
|
||||
q[1] = -n[0]*p[2];
|
||||
q[2] = n[0]*p[1];
|
||||
}
|
||||
else {
|
||||
// choose p in x-y plane
|
||||
SimdScalar a = n[0]*n[0] + n[1]*n[1];
|
||||
SimdScalar k = dRecipSqrt (a);
|
||||
p[0] = -n[1]*k;
|
||||
p[1] = n[0]*k;
|
||||
p[2] = 0;
|
||||
// set q = n x p
|
||||
q[0] = -n[2]*p[1];
|
||||
q[1] = n[2]*p[0];
|
||||
q[2] = a*k;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void ContactJoint::GetInfo2(Info2 *info)
|
||||
{
|
||||
|
||||
int s = info->rowskip;
|
||||
int s2 = 2*s;
|
||||
|
||||
float swapFactor = m_swapBodies ? -1.f : 1.f;
|
||||
|
||||
// get normal, with sign adjusted for body1/body2 polarity
|
||||
dVector3 normal;
|
||||
|
||||
|
||||
ManifoldPoint& point = m_manifold->GetContactPoint(m_index);
|
||||
|
||||
normal[0] = swapFactor*point.m_normalWorldOnB[0];
|
||||
normal[1] = swapFactor*point.m_normalWorldOnB[1];
|
||||
normal[2] = swapFactor*point.m_normalWorldOnB[2];
|
||||
normal[3] = 0; // @@@ hmmm
|
||||
|
||||
// if (GetBody0())
|
||||
SimdVector3 relativePositionA;
|
||||
{
|
||||
relativePositionA = point.GetPositionWorldOnA() - m_body0->getCenterOfMassPosition();
|
||||
dVector3 c1;
|
||||
c1[0] = relativePositionA[0];
|
||||
c1[1] = relativePositionA[1];
|
||||
c1[2] = relativePositionA[2];
|
||||
|
||||
// set jacobian for normal
|
||||
info->J1l[0] = normal[0];
|
||||
info->J1l[1] = normal[1];
|
||||
info->J1l[2] = normal[2];
|
||||
dCROSS (info->J1a,=,c1,normal);
|
||||
|
||||
}
|
||||
// if (GetBody1())
|
||||
SimdVector3 relativePositionB;
|
||||
{
|
||||
dVector3 c2;
|
||||
relativePositionB = point.GetPositionWorldOnB() - m_body1->getCenterOfMassPosition();
|
||||
|
||||
// for (i=0; i<3; i++) c2[i] = j->contact.geom.pos[i] -
|
||||
// j->node[1].body->pos[i];
|
||||
c2[0] = relativePositionB[0];
|
||||
c2[1] = relativePositionB[1];
|
||||
c2[2] = relativePositionB[2];
|
||||
|
||||
info->J2l[0] = -normal[0];
|
||||
info->J2l[1] = -normal[1];
|
||||
info->J2l[2] = -normal[2];
|
||||
dCROSS (info->J2a,= -,c2,normal);
|
||||
}
|
||||
|
||||
SimdScalar k = info->fps * info->erp;
|
||||
|
||||
float depth = -point.GetDistance();
|
||||
// if (depth < 0.f)
|
||||
// depth = 0.f;
|
||||
|
||||
info->c[0] = k * depth;
|
||||
//float maxvel = .2f;
|
||||
|
||||
// if (info->c[0] > maxvel)
|
||||
// info->c[0] = maxvel;
|
||||
|
||||
|
||||
//can override it, not necessary
|
||||
// info->cfm[0] = 0.f;
|
||||
// info->cfm[1] = 0.f;
|
||||
// info->cfm[2] = 0.f;
|
||||
|
||||
|
||||
|
||||
// set LCP limits for normal
|
||||
info->lo[0] = 0;
|
||||
info->hi[0] = 1e30f;//dInfinity;
|
||||
info->lo[1] = 0;
|
||||
info->hi[1] = 0.f;
|
||||
info->lo[2] = 0.f;
|
||||
info->hi[2] = 0.f;
|
||||
|
||||
#define DO_THE_FRICTION_2
|
||||
#ifdef DO_THE_FRICTION_2
|
||||
// now do jacobian for tangential forces
|
||||
dVector3 t1,t2; // two vectors tangential to normal
|
||||
|
||||
dVector3 c1;
|
||||
c1[0] = relativePositionA[0];
|
||||
c1[1] = relativePositionA[1];
|
||||
c1[2] = relativePositionA[2];
|
||||
|
||||
dVector3 c2;
|
||||
c2[0] = relativePositionB[0];
|
||||
c2[1] = relativePositionB[1];
|
||||
c2[2] = relativePositionB[2];
|
||||
|
||||
//combined friction is available in the contact point
|
||||
float friction = FRICTION_CONSTANT*m_body0->getFriction() * m_body1->getFriction();
|
||||
|
||||
// first friction direction
|
||||
if (m_numRows >= 2)
|
||||
{
|
||||
|
||||
|
||||
|
||||
dPlaneSpace1 (normal,t1,t2);
|
||||
|
||||
info->J1l[s+0] = t1[0];
|
||||
info->J1l[s+1] = t1[1];
|
||||
info->J1l[s+2] = t1[2];
|
||||
dCROSS (info->J1a+s,=,c1,t1);
|
||||
if (1) { //j->node[1].body) {
|
||||
info->J2l[s+0] = -t1[0];
|
||||
info->J2l[s+1] = -t1[1];
|
||||
info->J2l[s+2] = -t1[2];
|
||||
dCROSS (info->J2a+s,= -,c2,t1);
|
||||
}
|
||||
// set right hand side
|
||||
if (0) {//j->contact.surface.mode & dContactMotion1) {
|
||||
//info->c[1] = j->contact.surface.motion1;
|
||||
}
|
||||
// set LCP bounds and friction index. this depends on the approximation
|
||||
// mode
|
||||
//1e30f
|
||||
|
||||
|
||||
info->lo[1] = -friction;//-j->contact.surface.mu;
|
||||
info->hi[1] = friction;//j->contact.surface.mu;
|
||||
if (1)//j->contact.surface.mode & dContactApprox1_1)
|
||||
info->findex[1] = 0;
|
||||
|
||||
// set slip (constraint force mixing)
|
||||
if (0)//j->contact.surface.mode & dContactSlip1)
|
||||
{
|
||||
// info->cfm[1] = j->contact.surface.slip1;
|
||||
} else
|
||||
{
|
||||
//info->cfm[1] = 0.f;
|
||||
}
|
||||
}
|
||||
|
||||
// second friction direction
|
||||
if (m_numRows >= 3) {
|
||||
info->J1l[s2+0] = t2[0];
|
||||
info->J1l[s2+1] = t2[1];
|
||||
info->J1l[s2+2] = t2[2];
|
||||
dCROSS (info->J1a+s2,=,c1,t2);
|
||||
if (1) { //j->node[1].body) {
|
||||
info->J2l[s2+0] = -t2[0];
|
||||
info->J2l[s2+1] = -t2[1];
|
||||
info->J2l[s2+2] = -t2[2];
|
||||
dCROSS (info->J2a+s2,= -,c2,t2);
|
||||
}
|
||||
|
||||
// set right hand side
|
||||
if (0){//j->contact.surface.mode & dContactMotion2) {
|
||||
//info->c[2] = j->contact.surface.motion2;
|
||||
}
|
||||
// set LCP bounds and friction index. this depends on the approximation
|
||||
// mode
|
||||
if (0){//j->contact.surface.mode & dContactMu2) {
|
||||
//info->lo[2] = -j->contact.surface.mu2;
|
||||
//info->hi[2] = j->contact.surface.mu2;
|
||||
}
|
||||
else {
|
||||
info->lo[2] = -friction;
|
||||
info->hi[2] = friction;
|
||||
}
|
||||
if (0)//j->contact.surface.mode & dContactApprox1_2)
|
||||
|
||||
{
|
||||
info->findex[2] = 0;
|
||||
}
|
||||
// set slip (constraint force mixing)
|
||||
if (0) //j->contact.surface.mode & dContactSlip2)
|
||||
|
||||
{
|
||||
//info->cfm[2] = j->contact.surface.slip2;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
#endif //DO_THE_FRICTION_2
|
||||
|
||||
}
|
||||
|
||||
@@ -1,50 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef CONTACT_JOINT_H
|
||||
#define CONTACT_JOINT_H
|
||||
|
||||
#include "BU_Joint.h"
|
||||
class RigidBody;
|
||||
class PersistentManifold;
|
||||
|
||||
class ContactJoint : public BU_Joint
|
||||
{
|
||||
PersistentManifold* m_manifold;
|
||||
int m_index;
|
||||
bool m_swapBodies;
|
||||
RigidBody* m_body0;
|
||||
RigidBody* m_body1;
|
||||
|
||||
|
||||
public:
|
||||
|
||||
ContactJoint() {};
|
||||
|
||||
ContactJoint(PersistentManifold* manifold,int index,bool swap,RigidBody* body0,RigidBody* body1);
|
||||
|
||||
//BU_Joint interface for solver
|
||||
|
||||
virtual void GetInfo1(Info1 *info);
|
||||
|
||||
virtual void GetInfo2(Info2 *info);
|
||||
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif //CONTACT_JOINT_H
|
||||
|
||||
@@ -1,3 +1,3 @@
|
||||
PROJECT(BULLET_PHYSICS)
|
||||
|
||||
SUBDIRS(LinearMath Bullet BulletDynamics Demos Extras)
|
||||
SUBDIRS(src Demos Extras)
|
||||
|
||||
@@ -16,7 +16,7 @@ subject to the following restrictions:
|
||||
#include "BspConverter.h"
|
||||
#include "BspLoader.h"
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
|
||||
void BspConverter::convertBsp(BspLoader& bspLoader,float scaling)
|
||||
{
|
||||
@@ -86,7 +86,7 @@ void BspConverter::convertBsp(BspLoader& bspLoader,float scaling)
|
||||
std::vector<SimdVector3> vertices;
|
||||
|
||||
getVerticesFromPlaneEquations(planeEquations,vertices);
|
||||
printf("getVerticesFromPlaneEquations returned %i\n",vertices.size());
|
||||
printf("getVerticesFromPlaneEquations returned %i\n",(int)vertices.size());
|
||||
|
||||
bool isEntity = false;
|
||||
SimdVector3 entityTarget(0.f,0.f,0.f);
|
||||
|
||||
@@ -18,7 +18,7 @@ subject to the following restrictions:
|
||||
|
||||
class BspLoader;
|
||||
#include <vector>
|
||||
#include "SimdVector3.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
|
||||
///BspConverter turns a loaded bsp level into convex parts (vertices)
|
||||
class BspConverter
|
||||
@@ -26,7 +26,9 @@ class BspConverter
|
||||
public:
|
||||
|
||||
void convertBsp(BspLoader& bspLoader,float scaling);
|
||||
|
||||
virtual ~BspConverter()
|
||||
{
|
||||
}
|
||||
///Utility function to create vertices from a Quake Brush. Brute force but it works.
|
||||
///Bit overkill to use QHull package
|
||||
void getVerticesFromPlaneEquations(const std::vector<SimdVector3>& planeEquations , std::vector<SimdVector3>& verticesOut );
|
||||
|
||||
@@ -16,33 +16,10 @@ subject to the following restrictions:
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
|
||||
//#include "GL_LineSegmentShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/StaticPlaneShape.h"
|
||||
#include "CollisionShapes/ConvexHullShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
#include "CollisionShapes/ConvexTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
|
||||
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -21,36 +21,17 @@ subject to the following restrictions:
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "ParallelPhysicsEnvironment.h"
|
||||
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "MyMotionState.h"
|
||||
//#include "GL_LineSegmentShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/StaticPlaneShape.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/BvhTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
|
||||
#include "ParallelIslandDispatcher.h"
|
||||
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
#include "CollisionDispatch/SphereSphereCollisionAlgorithm.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -14,7 +14,7 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "MyMotionState.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
|
||||
MyMotionState::MyMotionState()
|
||||
{
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#define MY_MOTIONSTATE_H
|
||||
|
||||
#include "PHY_IMotionState.h"
|
||||
#include <SimdTransform.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
|
||||
|
||||
class MyMotionState : public PHY_IMotionState
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/Extras/LibXML ${BULLET_PHYSICS_SOURCE_DIR}/Extras/LibXML/include ${BULLET_PHYSICS_SOURCE_DIR}/Extras/COLLADA_DOM/include/1.4 ${BULLET_PHYSICS_SOURCE_DIR}/Extras/COLLADA_DOM/include ${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/Extras/LibXML ${BULLET_PHYSICS_SOURCE_DIR}/Extras/LibXML/include ${BULLET_PHYSICS_SOURCE_DIR}/Extras/COLLADA_DOM/include/1.4 ${BULLET_PHYSICS_SOURCE_DIR}/Extras/COLLADA_DOM/include ${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -18,17 +18,17 @@ subject to the following restrictions:
|
||||
#include "dae.h"
|
||||
#include "dom/domCOLLADA.h"
|
||||
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/StaticPlaneShape.h"
|
||||
#include "CollisionShapes/ConvexHullShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
#include "CollisionShapes/ConvexTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCylinderShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btStaticPlaneShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleMesh.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleMeshShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
|
||||
#include "BulletCollision/CollisionShapes/btCompoundShape.h"
|
||||
|
||||
#include "CcdPhysicsController.h"
|
||||
|
||||
|
||||
@@ -18,8 +18,8 @@ subject to the following restrictions:
|
||||
#ifndef COLLADA_CONVERTER_H
|
||||
#define COLLADA_CONVERTER_H
|
||||
|
||||
#include "SimdTransform.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
|
||||
class CollisionShape;
|
||||
class PHY_IPhysicsController;
|
||||
|
||||
@@ -15,19 +15,13 @@ subject to the following restrictions:
|
||||
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
|
||||
//COLLADA_DOM and LibXML source code are included in Extras/ folder.
|
||||
//COLLADA_DOM should compile under all platforms, and is enabled by default.
|
||||
|
||||
|
||||
@@ -19,21 +19,23 @@ subject to the following restrictions:
|
||||
/// See the define CATCH_DEGENERATE_TETRAHEDRON in Bullet's VoronoiSimplexSolver.cpp
|
||||
///
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/GjkPairDetector.h"
|
||||
#include "NarrowPhaseCollision/PointCollector.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
///This low-level internal demo does intentionally NOT use the btBulletCollisionCommon.h header
|
||||
///It needs internal access
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btPointCollector.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
|
||||
#include "CollisionDemo.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "GlutStuff.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
|
||||
float yaw=0.f,pitch=0.f,roll=0.f;
|
||||
|
||||
@@ -19,17 +19,11 @@ subject to the following restrictions:
|
||||
///
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "CollisionShapes/ConvexHullShape.h"
|
||||
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionDispatch/CollisionWorld.h"
|
||||
#include "CollisionDispatch/CollisionObject.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "IDebugDraw.h"
|
||||
//include common Bullet Collision Detection headerfiles
|
||||
#include "btBulletCollisionCommon.h"
|
||||
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "CollisionInterfaceDemo.h"
|
||||
#include "GlutStuff.h"
|
||||
|
||||
@@ -16,19 +16,8 @@ subject to the following restrictions:
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "MyMotionState.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
|
||||
#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/BvhTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
#include "GLDebugDrawer.h"
|
||||
#include "PHY_Pro.h"
|
||||
#include "ConcaveDemo.h"
|
||||
|
||||
@@ -14,7 +14,7 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "MyMotionState.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
|
||||
MyMotionState::MyMotionState()
|
||||
{
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#define MY_MOTIONSTATE_H
|
||||
|
||||
#include "PHY_IMotionState.h"
|
||||
#include <SimdTransform.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
|
||||
|
||||
class MyMotionState : public PHY_IMotionState
|
||||
|
||||
@@ -16,15 +16,8 @@ subject to the following restrictions:
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "MyMotionState.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
@@ -14,7 +14,7 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "MyMotionState.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
|
||||
MyMotionState::MyMotionState()
|
||||
{
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#define MY_MOTIONSTATE_H
|
||||
|
||||
#include "PHY_IMotionState.h"
|
||||
#include <SimdTransform.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
|
||||
|
||||
class MyMotionState : public PHY_IMotionState
|
||||
|
||||
@@ -18,26 +18,28 @@
|
||||
Also comparision with Algebraic CCD and Interval Arithmetic methods (Stephane Redon)
|
||||
*/
|
||||
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/MinkowskiSumShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/GjkPairDetector.h"
|
||||
#include "NarrowPhaseCollision/GjkConvexCast.h"
|
||||
#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
|
||||
#include "NarrowPhaseCollision/ContinuousConvexCollision.h"
|
||||
///This low level demo need internal access, and intentionally doesn't include the btBulletCollisionCommon.h headerfile
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h"
|
||||
|
||||
#include "SimdTransformUtil.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
|
||||
|
||||
#include "LinearMath/SimdTransformUtil.h"
|
||||
#include "DebugCastResult.h"
|
||||
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "ContinuousConvexCollision.h"
|
||||
|
||||
@@ -19,27 +19,10 @@ subject to the following restrictions:
|
||||
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
//#include "GL_LineSegmentShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/ConvexTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
|
||||
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
@@ -20,15 +20,15 @@ subject to the following restrictions:
|
||||
///
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "CollisionShapes/ConvexHullShape.h"
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/GjkPairDetector.h"
|
||||
#include "NarrowPhaseCollision/PointCollector.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
|
||||
#include "BulletDynamics/NarrowPhaseCollision/btPointCollector.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#ifdef WIN32 //needed for glut.h
|
||||
|
||||
@@ -24,8 +24,8 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include <GL/glut.h>
|
||||
#include "GlutStuff.h"
|
||||
@@ -34,11 +34,11 @@ subject to the following restrictions:
|
||||
#include <list>
|
||||
#include <time.h>
|
||||
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
|
||||
#include "NarrowPhaseCollision/EpaCommon.h"
|
||||
#include "NarrowPhaseCollision/EpaVertex.h"
|
||||
@@ -46,7 +46,7 @@ subject to the following restrictions:
|
||||
#include "NarrowPhaseCollision/EpaFace.h"
|
||||
#include "NarrowPhaseCollision/EpaPolyhedron.h"
|
||||
#include "NarrowPhaseCollision/Epa.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
#include "NarrowPhaseCollision/EpaPenetrationDepthSolver.h"
|
||||
EpaPenetrationDepthSolver epaPenDepthSolver;
|
||||
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -23,36 +23,12 @@ subject to the following restrictions:
|
||||
#include "ParallelPhysicsEnvironment.h"
|
||||
|
||||
#include "CcdPhysicsController.h"
|
||||
//#include "GL_LineSegmentShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/StaticPlaneShape.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/BvhTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "Vehicle/RaycastVehicle.h"
|
||||
#include "PHY_IVehicle.h"
|
||||
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
|
||||
#include "ParallelIslandDispatcher.h"
|
||||
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
@@ -19,23 +19,25 @@
|
||||
Also comparision with Algebraic CCD and Interval Arithmetic methods (Stephane Redon)
|
||||
*/
|
||||
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/MinkowskiSumShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/GjkPairDetector.h"
|
||||
#include "NarrowPhaseCollision/GjkConvexCast.h"
|
||||
#include "NarrowPhaseCollision/ContinuousConvexCollision.h"
|
||||
#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
|
||||
///Low level demo, doesn't include btBulletCollisionCommon.h
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h"
|
||||
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
|
||||
|
||||
#ifdef USE_ALGEBRAIC_CCD
|
||||
#include "NarrowPhaseCollision/BU_CollisionPair.h"
|
||||
#endif //USE_ALGEBRAIC_CCD
|
||||
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
|
||||
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "LinearConvexCastDemo.h"
|
||||
@@ -119,8 +121,8 @@ void LinearConvexCastDemo::clientMoveAndDisplay()
|
||||
displayCallback();
|
||||
}
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
|
||||
static VoronoiSimplexSolver sVoronoiSimplexSolver;
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ if $(GLUT.AVAILABLE) = "yes"
|
||||
rule BulletDemo
|
||||
{
|
||||
Application $(<) : $(>) : noinstall console nomanifest ;
|
||||
LinkWith $(<) : bullet bulletopenglsupport bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
LinkWith $(<) : bulletcollision bulletopenglsupport bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
CFlags $(<) :
|
||||
[ FIncludes $(TOP)/Demos/OpenGL ]
|
||||
[ FIncludes $(TOP)/Extras/PhysicsInterface/CcdPhysics ]
|
||||
@@ -24,7 +24,7 @@ if $(GLUT.AVAILABLE) = "yes"
|
||||
rule ExtraDemo
|
||||
{
|
||||
Application $(<) : $(>) : noinstall console nomanifest ;
|
||||
LinkWith $(<) : collada-dom libxml convexdecomposition bullet bulletopenglsupport bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
LinkWith $(<) : collada-dom libxml convexdecomposition bulletcollision bulletopenglsupport bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
CFlags $(<) :
|
||||
[ FIncludes $(TOP)/Demos/OpenGL ]
|
||||
[ FIncludes $(TOP)/Extras/PhysicsInterface/CcdPhysics ]
|
||||
@@ -62,7 +62,7 @@ else
|
||||
rule BulletBasicDemo
|
||||
{
|
||||
Application $(<) : $(>) : noinstall console nomanifest ;
|
||||
LinkWith $(<) : bullet bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
LinkWith $(<) : bulletcollision bulletphysicsinterfacecommon bulletccdphysics bulletmath ;
|
||||
CFlags $(<) :
|
||||
[ FIncludes $(TOP)/Extras/PhysicsInterface/CcdPhysics ]
|
||||
[ FIncludes $(TOP)/Extras/PhysicsInterface/Common ]
|
||||
|
||||
@@ -47,7 +47,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics ${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
ADD_LIBRARY(LibOpenGLSupport
|
||||
@@ -59,4 +59,5 @@ ADD_LIBRARY(LibOpenGLSupport
|
||||
GLDebugDrawer.cpp
|
||||
GlutStuff.cpp
|
||||
RenderTexture.cpp
|
||||
DemoApplication.cpp
|
||||
)
|
||||
|
||||
@@ -16,8 +16,8 @@ subject to the following restrictions:
|
||||
#ifndef DEBUG_CAST_RESULT_H
|
||||
#define DEBUG_CAST_RESULT_H
|
||||
|
||||
#include "NarrowPhaseCollision/ConvexCast.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexCast.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#ifdef WIN32
|
||||
#include <windows.h>
|
||||
|
||||
@@ -14,16 +14,16 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "DemoApplication.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"//picking
|
||||
#include "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h"//picking
|
||||
#include "PHY_Pro.h"
|
||||
#include "CollisionShapes/CollisionShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "quickprof.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "BMF_Api.h"
|
||||
|
||||
int numObjects = 0;
|
||||
|
||||
@@ -35,9 +35,9 @@ subject to the following restrictions:
|
||||
#include <math.h>
|
||||
|
||||
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdMatrix3x3.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdMatrix3x3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
|
||||
class CcdPhysicsEnvironment;
|
||||
class CcdPhysicsController;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
|
||||
#ifdef WIN32 //needed for glut.h
|
||||
#include <windows.h>
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#ifndef GL_DEBUG_DRAWER_H
|
||||
#define GL_DEBUG_DRAWER_H
|
||||
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -27,19 +27,19 @@ subject to the following restrictions:
|
||||
#endif
|
||||
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#include "CollisionShapes/PolyhedralConvexShape.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btPolyhedralConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleMeshShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCylinderShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCompoundShape.h"
|
||||
|
||||
#include "CollisionShapes/ConvexTriangleMeshShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h"
|
||||
|
||||
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
//for debugmodes
|
||||
#include "BMF_Api.h"
|
||||
#include <stdio.h> //printf debugging
|
||||
|
||||
@@ -16,7 +16,7 @@ subject to the following restrictions:
|
||||
#define GL_SHAPE_DRAWER_H
|
||||
|
||||
class CollisionShape;
|
||||
#include "SimdVector3.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
|
||||
/// OpenGL shape drawing
|
||||
class GL_ShapeDrawer
|
||||
|
||||
@@ -13,7 +13,7 @@ subject to the following restrictions:
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
#ifdef WIN32
|
||||
#include <windows.h>
|
||||
@@ -26,7 +26,7 @@ subject to the following restrictions:
|
||||
#else
|
||||
#include <GL/gl.h>
|
||||
#endif
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
|
||||
GL_Simplex1to4::GL_Simplex1to4()
|
||||
:m_simplexSolver(0)
|
||||
|
||||
@@ -15,9 +15,9 @@ subject to the following restrictions:
|
||||
#ifndef GL_SIMPLEX_1TO4_H
|
||||
#define GL_SIMPLEX_1TO4_H
|
||||
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
|
||||
///GL_Simplex1to4 is a class to debug a Simplex Solver with 1 to 4 points.
|
||||
///Can be used by GJK.
|
||||
|
||||
@@ -16,7 +16,7 @@ subject to the following restrictions:
|
||||
#ifndef RENDER_TEXTURE_H
|
||||
#define RENDER_TEXTURE_H
|
||||
|
||||
#include "SimdVector3.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "BMF_FontData.h"
|
||||
|
||||
///
|
||||
|
||||
@@ -16,31 +16,33 @@ Raytracer uses the Convex Raycast to visualize the Collision Shapes/Minkowski Su
|
||||
Very basic raytracer, rendering into a texture.
|
||||
*/
|
||||
|
||||
///Low level demo, doesn't include btBulletCollisionCommon.h
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
|
||||
#include "Raytracer.h"
|
||||
#include "GlutStuff.h"
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
|
||||
#include "NarrowPhaseCollision/GjkConvexCast.h"
|
||||
#include "NarrowPhaseCollision/ContinuousConvexCollision.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
|
||||
#ifdef USE_ALGEBRAIC_CCD
|
||||
#include "NarrowPhaseCollision/BU_CollisionPair.h"
|
||||
#endif //USE_ALGEBRAIC_CCD
|
||||
|
||||
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/MultiSphereShape.h"
|
||||
#include "CollisionShapes/ConvexHullShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "CollisionShapes/MinkowskiSumShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btMultiSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btBoxShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCylinderShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -19,11 +19,11 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "GL_Simplex1to4.h"
|
||||
#include "SimdQuaternion.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdQuaternion.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "GL_ShapeDrawer.h"
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "SimplexDemo.h"
|
||||
#include "GlutStuff.h"
|
||||
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -15,25 +15,8 @@ subject to the following restrictions:
|
||||
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
|
||||
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
|
||||
#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/BvhTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
#include "GLDebugDrawer.h"
|
||||
#include "PHY_Pro.h"
|
||||
#include "UserCollisionAlgorithm.h"
|
||||
@@ -41,7 +24,7 @@ subject to the following restrictions:
|
||||
#include "GlutStuff.h"
|
||||
|
||||
//The user defined collision algorithm
|
||||
#include "CollisionDispatch/SphereSphereCollisionAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
|
||||
|
||||
GLDebugDrawer debugDrawer;
|
||||
|
||||
|
||||
@@ -48,7 +48,7 @@ ELSE (WIN32)
|
||||
ENDIF (WIN32)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Demos/OpenGL ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
|
||||
@@ -21,38 +21,15 @@ subject to the following restrictions:
|
||||
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "ParallelPhysicsEnvironment.h"
|
||||
|
||||
#include "CcdPhysicsController.h"
|
||||
//#include "GL_LineSegmentShape.h"
|
||||
#include "CollisionShapes/BoxShape.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionShapes/StaticPlaneShape.h"
|
||||
#include "CollisionShapes/CompoundShape.h"
|
||||
#include "CollisionShapes/Simplex1to4Shape.h"
|
||||
#include "CollisionShapes/EmptyShape.h"
|
||||
#include "CollisionShapes/CylinderShape.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleIndexVertexArray.h"
|
||||
#include "CollisionShapes/BvhTriangleMeshShape.h"
|
||||
#include "CollisionShapes/TriangleMesh.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "Vehicle/RaycastVehicle.h"
|
||||
#include "PHY_IVehicle.h"
|
||||
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
|
||||
#include "ParallelIslandDispatcher.h"
|
||||
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
|
||||
#include "quickprof.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "GLDebugDrawer.h"
|
||||
|
||||
|
||||
2
Doxyfile
2
Doxyfile
@@ -267,7 +267,7 @@ WARN_LOGFILE =
|
||||
# directories like "/usr/src/myproject". Separate the files or directories
|
||||
# with spaces.
|
||||
|
||||
INPUT = Bullet BulletDynamics LinearMath Extras/PhysicsInterface Demos
|
||||
INPUT = src Extras/PhysicsInterface Demos
|
||||
|
||||
|
||||
# If the value of the INPUT tag contains directories, you can use the
|
||||
|
||||
@@ -15,8 +15,8 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
#include "BU_Collidable.h"
|
||||
#include "CollisionShapes/CollisionShape.h"
|
||||
#include <SimdTransform.h>
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include "BU_MotionStateInterface.h"
|
||||
|
||||
BU_Collidable::BU_Collidable(BU_MotionStateInterface& motion,PolyhedralConvexShape& shape,void* userPointer )
|
||||
|
||||
@@ -20,7 +20,7 @@ subject to the following restrictions:
|
||||
|
||||
class PolyhedralConvexShape;
|
||||
class BU_MotionStateInterface;
|
||||
#include <SimdPoint3.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
|
||||
class BU_Collidable
|
||||
{
|
||||
|
||||
@@ -22,9 +22,9 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
#include "BU_MotionStateInterface.h"
|
||||
#include "CollisionShapes/PolyhedralConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btPolyhedralConvexShape.h"
|
||||
#include <SimdMinMax.h>
|
||||
#include "SimdTransformUtil.h"
|
||||
#include "LinearMath/SimdTransformUtil.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -16,8 +16,8 @@ subject to the following restrictions:
|
||||
|
||||
#include "BU_EdgeEdge.h"
|
||||
#include "BU_Screwing.h"
|
||||
#include <SimdPoint3.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
|
||||
//#include "BU_IntervalArithmeticPolynomialSolver.h"
|
||||
#include "BU_AlgebraicPolynomialSolver.h"
|
||||
|
||||
@@ -18,13 +18,13 @@ subject to the following restrictions:
|
||||
#define BU_EDGEEDGE
|
||||
|
||||
class BU_Screwing;
|
||||
#include <SimdTransform.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <SimdVector3.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdVector3.h>
|
||||
|
||||
//class BUM_Point2;
|
||||
|
||||
#include <SimdScalar.h>
|
||||
#include <LinearMath/SimdScalar.h>
|
||||
|
||||
///BU_EdgeEdge implements algebraic time of impact calculation between two (angular + linear) moving edges.
|
||||
class BU_EdgeEdge
|
||||
|
||||
@@ -18,8 +18,8 @@ subject to the following restrictions:
|
||||
#define BU_MOTIONSTATE
|
||||
|
||||
|
||||
#include <SimdTransform.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <SimdQuaternion.h>
|
||||
|
||||
class BU_MotionStateInterface
|
||||
|
||||
@@ -15,7 +15,7 @@ subject to the following restrictions:
|
||||
#ifndef BUM_POLYNOMIAL_SOLVER_INTERFACE
|
||||
#define BUM_POLYNOMIAL_SOLVER_INTERFACE
|
||||
|
||||
#include <SimdScalar.h>
|
||||
#include <LinearMath/SimdScalar.h>
|
||||
//
|
||||
//BUM_PolynomialSolverInterface is interface class for polynomial root finding.
|
||||
//The number of roots is returned as a result, query GetRoot to get the actual solution.
|
||||
|
||||
@@ -18,9 +18,9 @@ subject to the following restrictions:
|
||||
#define B_SCREWING_H
|
||||
|
||||
|
||||
#include <SimdVector3.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <SimdTransform.h>
|
||||
#include <LinearMath/SimdVector3.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
|
||||
|
||||
#define SCREWEPSILON 0.00001f
|
||||
|
||||
@@ -17,9 +17,9 @@ subject to the following restrictions:
|
||||
|
||||
#include "BU_VertexPoly.h"
|
||||
#include "BU_Screwing.h"
|
||||
#include <SimdTransform.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <SimdVector3.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdVector3.h>
|
||||
|
||||
#define USE_ALGEBRAIC
|
||||
#ifdef USE_ALGEBRAIC
|
||||
|
||||
@@ -19,9 +19,9 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
class BU_Screwing;
|
||||
#include <SimdTransform.h>
|
||||
#include <SimdPoint3.h>
|
||||
#include <SimdScalar.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdScalar.h>
|
||||
|
||||
///BU_VertexPoly implements algebraic time of impact calculation between vertex and a plane.
|
||||
class BU_VertexPoly
|
||||
|
||||
@@ -14,9 +14,9 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "SphereSphereCollisionAlgorithm.h"
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionDispatch/CollisionObject.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||
|
||||
SphereSphereCollisionAlgorithm::SphereSphereCollisionAlgorithm(PersistentManifold* mf,const CollisionAlgorithmConstructionInfo& ci,BroadphaseProxy* proxy0,BroadphaseProxy* proxy1)
|
||||
: CollisionAlgorithm(ci),
|
||||
|
||||
@@ -16,9 +16,9 @@ subject to the following restrictions:
|
||||
#ifndef SPHERE_SPHERE_COLLISION_ALGORITHM_H
|
||||
#define SPHERE_SPHERE_COLLISION_ALGORITHM_H
|
||||
|
||||
#include "BroadphaseCollision/CollisionAlgorithm.h"
|
||||
#include "BroadphaseCollision/BroadphaseProxy.h"
|
||||
#include "CollisionDispatch/CollisionCreateFunc.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
|
||||
class PersistentManifold;
|
||||
|
||||
/// SphereSphereCollisionAlgorithm provides sphere-sphere collision detection.
|
||||
|
||||
@@ -15,19 +15,19 @@ subject to the following restrictions:
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#include "SimdScalar.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "SimdMinMax.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/SimdMinMax.h"
|
||||
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
|
||||
#include <vector>
|
||||
#include <list>
|
||||
#include <algorithm>
|
||||
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
|
||||
#include "NarrowPhaseCollision/EpaCommon.h"
|
||||
|
||||
|
||||
@@ -14,9 +14,9 @@ subject to the following restrictions:
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
#include "SimdScalar.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
|
||||
#include "NarrowPhaseCollision/EpaCommon.h"
|
||||
|
||||
|
||||
@@ -14,17 +14,17 @@ subject to the following restrictions:
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
#include "SimdScalar.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "SimdMinMax.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/SimdMinMax.h"
|
||||
|
||||
#include <list>
|
||||
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
|
||||
#include "NarrowPhaseCollision/EpaCommon.h"
|
||||
|
||||
@@ -33,7 +33,7 @@ subject to the following restrictions:
|
||||
#include "NarrowPhaseCollision/EpaFace.h"
|
||||
#include "NarrowPhaseCollision/EpaPolyhedron.h"
|
||||
#include "NarrowPhaseCollision/Epa.h"
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
#include "NarrowPhaseCollision/EpaPenetrationDepthSolver.h"
|
||||
|
||||
SimdScalar g_GJKMaxRelError = 1e-3f;
|
||||
|
||||
@@ -14,9 +14,9 @@ subject to the following restrictions:
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
#include "SimdScalar.h"
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdPoint3.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdPoint3.h"
|
||||
#include "Memory2.h"
|
||||
|
||||
#include <list>
|
||||
|
||||
@@ -12,8 +12,8 @@
|
||||
#ifndef COMBINED_SIMPLEX_SOLVER
|
||||
#define COMBINED_SIMPLEX_SOLVER
|
||||
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "Solid3JohnsonSimplexSolver.h"
|
||||
|
||||
/// CombinedSimplexSolver runs both Solid and Voronoi Simplex Solver for comparison
|
||||
|
||||
@@ -24,9 +24,9 @@
|
||||
#include "Solid3EpaPenetrationDepth.h"
|
||||
#include <algorithm>
|
||||
#include <vector>
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "GEN_MinMax.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "LinearMath/GenMinMax.h"
|
||||
|
||||
#define ASSERT_MESSAGE
|
||||
|
||||
|
||||
@@ -25,7 +25,7 @@
|
||||
#define SOLID3_EPA_PENETRATION_DEPTH_H
|
||||
|
||||
|
||||
#include "NarrowPhaseCollision/ConvexPenetrationDepthSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
|
||||
|
||||
/// Solid3EpaPenetrationDepth contains the 'Expanding Polytope Algorithm' from Solid 3.5
|
||||
class Solid3EpaPenetrationDepth : public ConvexPenetrationDepthSolver
|
||||
|
||||
@@ -22,7 +22,7 @@
|
||||
*/
|
||||
|
||||
#include "Solid3JohnsonSimplexSolver.h"
|
||||
#include "GEN_MinMax.h"
|
||||
#include "LinearMath/GenMinMax.h"
|
||||
|
||||
//#define USE_BACKUP_PROCEDURE
|
||||
//#define FAST_CLOSEST
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
#ifndef SOLID3JOHNSON_SIMPLEX_SOLVER_H
|
||||
#define SOLID3JOHNSON_SIMPLEX_SOLVER_H
|
||||
|
||||
#include "NarrowPhaseCollision/SimplexSolverInterface.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
|
||||
|
||||
//#define JOHNSON_ROBUST
|
||||
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,5 +1,5 @@
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Bullet ${BULLET_PHYSICS_SOURCE_DIR}/BulletDynamics ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
|
||||
)
|
||||
|
||||
ADD_LIBRARY(LibCcdPhysicsInterface
|
||||
@@ -8,4 +8,4 @@ ADD_LIBRARY(LibCcdPhysicsInterface
|
||||
ParallelIslandDispatcher.cpp
|
||||
ParallelPhysicsEnvironment.cpp
|
||||
SimulationIsland.cpp
|
||||
)
|
||||
)
|
||||
|
||||
@@ -15,16 +15,16 @@ subject to the following restrictions:
|
||||
|
||||
#include "CcdPhysicsController.h"
|
||||
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "PHY_IMotionState.h"
|
||||
#include "BroadphaseCollision/BroadphaseProxy.h"
|
||||
#include "BroadphaseCollision/BroadphaseInterface.h"
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "SimdTransformUtil.h"
|
||||
#include "LinearMath/SimdTransformUtil.h"
|
||||
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
|
||||
class BP_Proxy;
|
||||
|
||||
@@ -37,7 +37,7 @@ bool gDisableDeactivation = false;
|
||||
float gLinearSleepingTreshold = 0.8f;
|
||||
float gAngularSleepingTreshold = 1.0f;
|
||||
|
||||
#include "Dynamics/MassProps.h"
|
||||
#include "BulletDynamics/Dynamics/btMassProps.h"
|
||||
|
||||
SimdVector3 startVel(0,0,0);//-10000);
|
||||
CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
|
||||
|
||||
@@ -21,15 +21,15 @@ subject to the following restrictions:
|
||||
|
||||
/// PHY_IPhysicsController is the abstract simplified Interface to a physical object.
|
||||
/// It contains the IMotionState and IDeformableMesh Interfaces.
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdScalar.h"
|
||||
#include "SimdMatrix3x3.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdMatrix3x3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
|
||||
#include "PHY_IMotionState.h"
|
||||
|
||||
#include "BroadphaseCollision/BroadphaseProxy.h" //for CollisionShape access
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" //for CollisionShape access
|
||||
class CollisionShape;
|
||||
|
||||
extern float gDeactivationTime;
|
||||
|
||||
@@ -20,62 +20,62 @@ subject to the following restrictions:
|
||||
#include "CcdPhysicsController.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include "SimdTransform.h"
|
||||
#include "Dynamics/RigidBody.h"
|
||||
#include "BroadphaseCollision/BroadphaseInterface.h"
|
||||
#include "BroadphaseCollision/SimpleBroadphase.h"
|
||||
#include "BroadphaseCollision/AxisSweep3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btSimpleBroadphase.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btAxisSweep3.h"
|
||||
|
||||
#include "CollisionDispatch/CollisionWorld.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
|
||||
|
||||
#include "CollisionShapes/ConvexShape.h"
|
||||
#include "CollisionShapes/ConeShape.h"
|
||||
#include "CollisionDispatch/SimulationIslandManager.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
|
||||
|
||||
#include "BroadphaseCollision/Dispatcher.h"
|
||||
#include "NarrowPhaseCollision/PersistentManifold.h"
|
||||
#include "CollisionShapes/TriangleMeshShape.h"
|
||||
#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleMeshShape.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||
|
||||
|
||||
//profiling/timings
|
||||
#include "quickprof.h"
|
||||
#include "LinearMath/GenQuickprof.h"
|
||||
|
||||
|
||||
#include "IDebugDraw.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
|
||||
#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
|
||||
#include "NarrowPhaseCollision/GjkConvexCast.h"
|
||||
#include "NarrowPhaseCollision/ContinuousConvexCollision.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
|
||||
|
||||
|
||||
#include "CollisionDispatch/CollisionDispatcher.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "PHY_IMotionState.h"
|
||||
|
||||
#include "CollisionDispatch/EmptyCollisionAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h"
|
||||
|
||||
|
||||
|
||||
#include "CollisionShapes/SphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
|
||||
bool useIslands = true;
|
||||
|
||||
#ifdef NEW_BULLET_VEHICLE_SUPPORT
|
||||
#include "Vehicle/RaycastVehicle.h"
|
||||
#include "Vehicle/VehicleRaycaster.h"
|
||||
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
||||
#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
|
||||
|
||||
#include "Vehicle/WheelInfo.h"
|
||||
#include "BulletDynamics/Vehicle/btWheelInfo.h"
|
||||
#include "PHY_IVehicle.h"
|
||||
RaycastVehicle::VehicleTuning gTuning;
|
||||
|
||||
#endif //NEW_BULLET_VEHICLE_SUPPORT
|
||||
#include "AabbUtil2.h"
|
||||
#include "LinearMath/GenAabbUtil2.h"
|
||||
|
||||
#include "ConstraintSolver/ConstraintSolver.h"
|
||||
#include "ConstraintSolver/Point2PointConstraint.h"
|
||||
#include "ConstraintSolver/HingeConstraint.h"
|
||||
#include "ConstraintSolver/Generic6DofConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btConstraintSolver.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btHingeConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h"
|
||||
|
||||
|
||||
//#include "BroadphaseCollision/QueryDispatcher.h"
|
||||
@@ -87,7 +87,7 @@ void DrawRasterizerLine(const float* from,const float* to,int color);
|
||||
#endif
|
||||
|
||||
|
||||
#include "ConstraintSolver/ContactConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
@@ -1120,6 +1120,9 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
virtual ~DefaultVehicleRaycaster()
|
||||
{
|
||||
}
|
||||
/* struct VehicleRaycasterResult
|
||||
{
|
||||
VehicleRaycasterResult() :m_distFraction(-1.f){};
|
||||
|
||||
@@ -19,8 +19,8 @@ subject to the following restrictions:
|
||||
#include "PHY_IPhysicsEnvironment.h"
|
||||
#include <vector>
|
||||
class CcdPhysicsController;
|
||||
#include "SimdVector3.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
|
||||
|
||||
|
||||
@@ -29,12 +29,12 @@ class TypedConstraint;
|
||||
class SimulationIslandManager;
|
||||
class CollisionDispatcher;
|
||||
class Dispatcher;
|
||||
//#include "BroadphaseInterface.h"
|
||||
//#include "btBroadphaseInterface.h"
|
||||
|
||||
//switch on/off new vehicle support
|
||||
#define NEW_BULLET_VEHICLE_SUPPORT 1
|
||||
|
||||
#include "ConstraintSolver/ContactSolverInfo.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
|
||||
class WrapperVehicle;
|
||||
class PersistentManifold;
|
||||
|
||||
@@ -4,7 +4,7 @@ IncludeDir Extras/PhysicsInterface/Common ;
|
||||
|
||||
Library bulletccdphysics : [ Wildcard *.h *.cpp ] ;
|
||||
CFlags bulletccdphysics : [ FIncludes $(TOP)/Extras/PhysicsInterface/Common ] ;
|
||||
LibDepends bulletccdphysics : bullet bulletphysicsinterfacecommon bulletdynamics ;
|
||||
LibDepends bulletccdphysics : bulletcollision bulletphysicsinterfacecommon bulletdynamics ;
|
||||
|
||||
|
||||
InstallHeader [ Wildcard *.h ] : CcdPhysics ;
|
||||
|
||||
@@ -17,14 +17,14 @@ subject to the following restrictions:
|
||||
#include "ParallelIslandDispatcher.h"
|
||||
|
||||
|
||||
#include "BroadphaseCollision/CollisionAlgorithm.h"
|
||||
#include "CollisionDispatch/ConvexConvexAlgorithm.h"
|
||||
#include "CollisionDispatch/EmptyCollisionAlgorithm.h"
|
||||
#include "CollisionDispatch/ConvexConcaveCollisionAlgorithm.h"
|
||||
#include "CollisionDispatch/CompoundCollisionAlgorithm.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h"
|
||||
|
||||
#include "CollisionShapes/CollisionShape.h"
|
||||
#include "CollisionDispatch/CollisionObject.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||
#include <algorithm>
|
||||
|
||||
static int gNumManifold2 = 0;
|
||||
|
||||
@@ -16,18 +16,18 @@ subject to the following restrictions:
|
||||
#ifndef PARALLEL_ISLAND_DISPATCHER_H
|
||||
#define PARALLEL_ISLAND_DISPATCHER_H
|
||||
|
||||
#include "BroadphaseCollision/Dispatcher.h"
|
||||
#include "NarrowPhaseCollision/PersistentManifold.h"
|
||||
#include "CollisionDispatch/UnionFind.h"
|
||||
#include "CollisionDispatch/ManifoldResult.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
|
||||
#include "BulletCollision/CollisionDispatch/btUnionFind.h"
|
||||
#include "BulletCollision/CollisionDispatch/btManifoldResult.h"
|
||||
|
||||
#include "BroadphaseCollision/BroadphaseProxy.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
#include <vector>
|
||||
|
||||
class IDebugDraw;
|
||||
|
||||
|
||||
#include "CollisionDispatch/CollisionCreateFunc.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -18,9 +18,9 @@ subject to the following restrictions:
|
||||
#include "ParallelPhysicsEnvironment.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "ParallelIslandDispatcher.h"
|
||||
#include "CollisionDispatch/CollisionWorld.h"
|
||||
#include "ConstraintSolver/TypedConstraint.h"
|
||||
#include "CollisionDispatch/SimulationIslandManager.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
|
||||
#include "SimulationIsland.h"
|
||||
|
||||
|
||||
|
||||
@@ -14,15 +14,15 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "SimulationIsland.h"
|
||||
#include "SimdTransform.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "BroadphaseCollision/OverlappingPairCache.h"
|
||||
#include "CollisionShapes/CollisionShape.h"
|
||||
#include "BroadphaseCollision/Dispatcher.h"
|
||||
#include "ConstraintSolver/ContactSolverInfo.h"
|
||||
#include "ConstraintSolver/ConstraintSolver.h"
|
||||
#include "ConstraintSolver/TypedConstraint.h"
|
||||
#include "IDebugDraw.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btOverlappingPairCache.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btConstraintSolver.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
|
||||
extern float gContactBreakingTreshold;
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/LinearMath ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common }
|
||||
${BULLET_PHYSICS_SOURCE_DIR}src ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common }
|
||||
)
|
||||
|
||||
ADD_LIBRARY(LibPhysicsCommonInterface
|
||||
@@ -7,4 +7,4 @@ ADD_LIBRARY(LibPhysicsCommonInterface
|
||||
PHY_IPhysicsController.cpp
|
||||
PHY_IPhysicsEnvironment.cpp
|
||||
PHY_IVehicle.cpp
|
||||
)
|
||||
)
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user