moved files around

This commit is contained in:
ejcoumans
2006-05-25 19:18:29 +00:00
commit e061ec1ebf
1024 changed files with 349445 additions and 0 deletions

View File

@@ -0,0 +1,147 @@
#include "BVHTrimeshShape.h"
#define TRIMESH_INTERNAL //requires OPCODE for the AABB tree
#include <../ode/src/collision_trimesh_internal.h>
//Thanks AndrewONeil for the TrimeshBridge fix
BVHTrimeshShape::BVHTrimeshShape(dxTriMesh* trimesh)
: TriangleMeshShape(new TrimeshBridge(trimesh))
, m_triangleBridge( static_cast<TrimeshBridge*>(m_meshInterface))
{
}
BVHTrimeshShape::~BVHTrimeshShape ()
{
delete m_triangleBridge;
}
TrimeshBridge::TrimeshBridge(dxTriMesh* trimesh)
:m_trimesh(trimesh)
{
}
void TrimeshBridge::getLockedReadOnlyVertexIndexBase(const unsigned char **vertexbase, int& numverts,PHY_ScalarType& type, int& stride,const unsigned char **indexbase,int & indexstride,int& numfaces,PHY_ScalarType& indicestype,int subpart) const
{
numverts = m_trimesh->Data->Mesh.GetNbVertices();
(*vertexbase) = (unsigned char *)m_trimesh->Data->Mesh.GetVerts();
type = PHY_FLOAT;
stride = m_trimesh->Data->Mesh.GetVertexStride();
numfaces = m_trimesh->Data->Mesh.GetNbTriangles();
(*indexbase) = (unsigned char *)m_trimesh->Data->Mesh.GetTris();
indexstride = m_trimesh->Data->Mesh.GetTriStride();
indicestype = PHY_INTEGER;
}
void TrimeshBridge::getLockedVertexIndexBase(unsigned char **vertexbase, int& numverts,PHY_ScalarType& type, int& stride,unsigned char **indexbase,int & indexstride,int& numfaces,PHY_ScalarType& indicestype,int subpart)
{
numverts = m_trimesh->Data->Mesh.GetNbVertices();
(*vertexbase) = (unsigned char *)m_trimesh->Data->Mesh.GetVerts();
type = PHY_FLOAT;
stride = m_trimesh->Data->Mesh.GetVertexStride();
numfaces = m_trimesh->Data->Mesh.GetNbTriangles();
(*indexbase) = (unsigned char *)m_trimesh->Data->Mesh.GetTris();
indexstride = m_trimesh->Data->Mesh.GetTriStride();
indicestype = PHY_INTEGER;
}
#ifdef USE_AABB_TREE
//ProcessAllTriangles first gets the overlapping triangles using BVH culling
//and passes them on to the TriangleCallback
void BVHTrimeshShape::ProcessAllTriangles(TriangleCallback* callback,const SimdVector3& aabbMin,const SimdVector3& aabbMax) const
{
dxTriMesh* TriMesh = m_triangleBridge->m_trimesh;
// Init
const dVector3& TLPosition = *(const dVector3*)dGeomGetPosition(TriMesh);
const dMatrix3& TLRotation = *(const dMatrix3*)dGeomGetRotation(TriMesh);
SphereCollider& Collider = TriMesh->_SphereCollider;
SimdVector3 he = (aabbMax-aabbMin)*0.5f;
SimdVector3 cen = (aabbMax+aabbMin)*0.5f;
dVector3 aabbHalfExtents;
aabbHalfExtents[0] = he.x();
aabbHalfExtents[1] = he.y();
aabbHalfExtents[2] = he.z();
dVector3 Position;
Position[0]=cen.x();
Position[1]=cen.y();
Position[2]=cen.z();
dReal Radius = he.length();
// Bounding Sphere (from aabb)
Sphere Sphere;
Sphere.mCenter.x = Position[0];
Sphere.mCenter.y = Position[1];
Sphere.mCenter.z = Position[2];
Sphere.mRadius = Radius;
Matrix4x4 trimeshTransform;
MakeMatrix(TLPosition, TLRotation, trimeshTransform);
// bvhTraversal.getOverlappingPrimitiveIndices(
// indicesCache,
// Sphere,
// TriMesh->Data->BVTree,
// &trimeshTransform);
Collider.SetTemporalCoherence(false);
Collider.SetPrimitiveTests(false);
Collider.Collide(dxTriMesh::defaultSphereCache, Sphere, TriMesh->Data->BVTree, null,
&trimeshTransform);
// get results
int TriCount = Collider.GetNbTouchedPrimitives();
const int* Triangles = (const int*)Collider.GetTouchedPrimitives();
if (TriCount != 0){
int OutTriCount = 0;
for (int i = 0; i < TriCount; i++){
//what was this
//if (OutTriCount == (Flags & 0xffff)){
// break;
//}
const int& TriIndex = Triangles[i];
dVector3 dv[3];
FetchTriangle(TriMesh, TriIndex, TLPosition, TLRotation, dv);
SimdVector3 vts[3] =
{ SimdVector3(dv[0][0],dv[0][1],dv[0][2]),
SimdVector3 (dv[1][0],dv[1][1],dv[1][2]),
SimdVector3 (dv[2][0],dv[2][1],dv[2][2])
};
callback->ProcessTriangle(&vts[0]);
OutTriCount++;
}
if (OutTriCount)
{
}
}
}
#endif //USE_AABB_TREE

View File

@@ -0,0 +1,68 @@
#ifndef BVH_TRIMESH_SHAPE_H
#define BVH_TRIMESH_SHAPE_H
#include <ode/collision.h>
#include <ode/matrix.h>
#include <ode/rotation.h>
#include <ode/odemath.h>
#include <../ode/src/collision_util.h>
#include <../ode/src/collision_kernel.h>
#include <../ode/src/collision_kernel.h>
#include "CollisionShapes/TriangleMeshShape.h"
struct dxTriMesh;
///if this USE_AABB_TREE is not defined, it will brute force go through all triangles
#define USE_AABB_TREE
class TrimeshBridge : public StridingMeshInterface
{
public:
dxTriMesh* m_trimesh;
TrimeshBridge(dxTriMesh* trimesh);
virtual void getLockedVertexIndexBase(unsigned char **vertexbase, int& numverts,PHY_ScalarType& type, int& stride,unsigned char **indexbase,int & indexstride,int& numfaces,PHY_ScalarType& indicestype,int subpart=0);
virtual void getLockedReadOnlyVertexIndexBase(const unsigned char **vertexbase, int& numverts,PHY_ScalarType& type, int& stride,const unsigned char **indexbase,int & indexstride,int& numfaces,PHY_ScalarType& indicestype,int subpart=0) const;
/// unLockVertexBase finishes the access to a subpart of the triangle mesh
/// make a call to unLockVertexBase when the read and write access (using getLockedVertexIndexBase) is finished
virtual void unLockVertexBase(int subpart) {}
virtual void unLockReadOnlyVertexBase(int subpart) const {}
/// getNumSubParts returns the number of seperate subparts
/// each subpart has a continuous array of vertices and indices
virtual int getNumSubParts() const { return 1;}
virtual void preallocateVertices(int numverts){}
virtual void preallocateIndices(int numindices){}
};
/// BVHTrimeshShape bridges the Opcode to provide backwards compatibility with dxTriMesh.
/// You can also avoid using Opcode and use Bullet trimesh support See: BvhTriangleMeshShape
class BVHTrimeshShape : public TriangleMeshShape
{
TrimeshBridge * m_triangleBridge;
public:
BVHTrimeshShape(dxTriMesh* trimesh);
virtual ~BVHTrimeshShape ();
#ifdef USE_AABB_TREE
//ProcessAllTriangles first gets the overlapping triangles using BVH culling
//and passes them on to the TriangleCallback
void ProcessAllTriangles(TriangleCallback* callback,const SimdVector3& aabbMin,const SimdVector3& aabbMax) const;
#endif
};
#endif //BVH_TRIMESH_SHAPE_H

View File

@@ -0,0 +1,139 @@
#include "BulletOdeCollide.h"
//quick hack, we need internals, not just the public ode api
#include <../ode/src/collision_kernel.h>
#include "NarrowPhaseCollision/PersistentManifold.h"
#include "NarrowPhaseCollision/ManifoldPoint.h"
#include "BroadphaseCollision/CollisionAlgorithm.h"
#include "BulletOdeCollisionPair.h"
#include "../ode/src/collision_convex_internal.h"
#define CONTACT(p,skip) ((dContactGeom*) (((char*)p) + (skip)))
//Persistent collision pairs. Best is to store this in the broadphase/collision-pairs if the collision detection framework provides this
#define MAX_COLLISION_PAIRS 10000
static BulletOdeCollisionPair* sCollisionPair[MAX_COLLISION_PAIRS];
static int numActiveCollisionPairs = 0;
void InitBulletOdeCollide()
{
numActiveCollisionPairs = 0;
}
void ExitBulletOdeCollide()
{
//todo: cleanup memory
numActiveCollisionPairs = 0;
}
CollisionShape* GetCollisionShapeFromConvex(dGeomID geom)
{
dUASSERT (geom && geom->type == dConvexClass,"argument not a convex");
dxConvex* cnvx = (dxConvex*) geom;
return cnvx->m_bulletCollisionShape;
}
BulletOdeCollisionPair* FindCollisionPair(dGeomID o1,dGeomID o2)
{
int i;
for (i=0;i<numActiveCollisionPairs;i++)
{
if ( (sCollisionPair[i]->m_o1 == o1) &&
(sCollisionPair[i]->m_o2 == o2))
{
return sCollisionPair[i];
}
}
return 0;
}
void RemoveOdeGeomFromCollisionCache(dGeomID geom)
{
int i;
for (i=numActiveCollisionPairs-1;i>=0;i--)
{
if ( (sCollisionPair[i]->m_o1 == geom) ||
(sCollisionPair[i]->m_o2 == geom))
{
delete sCollisionPair[i];
sCollisionPair[i] = sCollisionPair[numActiveCollisionPairs-1];
numActiveCollisionPairs--;
}
}
}
int BulletOdeCollide(dGeomID o1,dGeomID o2,dContactGeom *contact,int maxContact,int skip)
{
//In order to have more then 1 point we use persistent manifold per overlapping pair
BulletOdeCollisionPair* collisionPair = FindCollisionPair(o1,o2);
if (!collisionPair)
{
if (numActiveCollisionPairs < MAX_COLLISION_PAIRS)
{
collisionPair = new BulletOdeCollisionPair(o1,o2);
sCollisionPair[numActiveCollisionPairs++] = collisionPair ;
} else
{
printf("overflow in collisionpair cache\n");
return 0;
}
}
//perform collision detection and recalculate the contact manifold
collisionPair->CalculateContacts();
//transfer contacts from PersistentManifold to gContactGeom
int validContacts = 0;
float maxDepth = -1e30f;
for (int i=0; i<collisionPair->m_manifold->GetNumContacts(); i++)
{
const ManifoldPoint& pt = collisionPair->m_manifold->GetContactPoint(i);
if (pt.GetDistance() < 0.f)
{
float depth = -pt.GetDistance();
//add contacts, and make sure to add the deepest contact in any case
if ((validContacts < maxContact) || (depth > maxDepth))
{
maxDepth = depth;
int contactIndex = validContacts;
if (contactIndex >= maxContact)
contactIndex = 0;
if (contactIndex < maxContact)
{
SimdVector3 pos = (pt.m_positionWorldOnB + pt.m_positionWorldOnA)*0.5f;
CONTACT(contact,contactIndex*skip)->depth = depth;
CONTACT(contact,contactIndex*skip)->pos[0] = pos.getX();
CONTACT(contact,contactIndex*skip)->pos[1] = pos.getY();
CONTACT(contact,contactIndex*skip)->pos[2] = pos.getZ();
CONTACT(contact,contactIndex*skip)->normal[0] = pt.m_normalWorldOnB.getX();
CONTACT(contact,contactIndex*skip)->normal[1] = pt.m_normalWorldOnB.getY();
CONTACT(contact,contactIndex*skip)->normal[2] = pt.m_normalWorldOnB.getZ();
CONTACT(contact,contactIndex*skip)->g1 = o1;
CONTACT(contact,contactIndex*skip)->g2 = o2;
}
if (validContacts < maxContact)
validContacts++;
}
}
}
//printf("numcontacts: %d",validContacts);
return validContacts;
}

View File

@@ -0,0 +1,13 @@
#ifndef _BULLET_ODE_COLLIDE_H
#define _BULLET_ODE_COLLIDE_H
#include <ode/common.h>
#include <ode/contact.h>
int BulletOdeCollide(dGeomID o1,dGeomID o2,dContactGeom *contact,int maxContacts,int skip);
void RemoveOdeGeomFromCollisionCache(dGeomID geom);
class CollisionShape* GetCollisionShapeFromConvex(dGeomID convex);
dGeomID dCreateConvex (dSpaceID space, class CollisionShape* shape);
void dGeomConvexGetLengths(dGeomID convex, dVector3 result);
#endif //_BULLET_ODE_COLLIDE_H

View File

@@ -0,0 +1,161 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="7.10"
Name="BulletOdeCollide"
ProjectGUID="{44672927-0084-4B70-8CDA-8697BF848C7F}"
RootNamespace="BulletOdeCollide"
Keyword="Win32Proj">
<Platforms>
<Platform
Name="Win32"/>
</Platforms>
<Configurations>
<Configuration
Name="Debug|Win32"
OutputDirectory="Debug"
IntermediateDirectory="Debug"
ConfigurationType="4"
CharacterSet="1">
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="../ode/include;../../Bullet;../../LinearMath;."
PreprocessorDefinitions="WIN32;_DEBUG;_LIB,BULLET_CONVEX_SUPPORT"
MinimalRebuild="TRUE"
BasicRuntimeChecks="3"
RuntimeLibrary="3"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="4"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
<Configuration
Name="Release|Win32"
OutputDirectory="Release"
IntermediateDirectory="Release"
ConfigurationType="4"
CharacterSet="1">
<Tool
Name="VCCLCompilerTool"
Optimization="2"
AdditionalIncludeDirectories="../ode/include;../../Bullet;../../LinearMath;."
PreprocessorDefinitions="WIN32;NDEBUG;_LIB,BULLET_CONVEX_SUPPORT"
RuntimeLibrary="2"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="3"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx"
UniqueIdentifier="{4FC737F1-C7A5-4376-A066-2A32D752A2FF}">
<File
RelativePath=".\BulletOdeCollide.cpp">
</File>
<File
RelativePath=".\BulletOdeCollisionPair.cpp">
</File>
<File
RelativePath=".\BulletOdeManifoldResult.cpp">
</File>
<File
RelativePath=".\BulletOdeTransformConvert.cpp">
</File>
<File
RelativePath="..\ode\ode\src\collision_convex.cpp">
</File>
<File
RelativePath=".\GeomToShape.cpp">
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl;inc;xsd"
UniqueIdentifier="{93995380-89BD-4b04-88EB-625FBE52EBFB}">
<File
RelativePath=".\BulletOdeCollide.h">
</File>
<File
RelativePath=".\BulletOdeCollisionPair.h">
</File>
<File
RelativePath=".\BulletOdeManifoldResult.h">
</File>
<File
RelativePath=".\BulletOdeTransformConvert.h">
</File>
<File
RelativePath=".\BVHTraversal.h">
</File>
<File
RelativePath=".\BVHTrimeshShape.h">
</File>
<File
RelativePath=".\GeomToShape.h">
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav"
UniqueIdentifier="{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}">
</Filter>
<File
RelativePath=".\VTune\BulletOdeCollide.vpj">
</File>
<File
RelativePath=".\ReadMe.txt">
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

View File

@@ -0,0 +1,184 @@
#include "BulletOdeCollisionPair.h"
#include "NarrowPhaseCollision/PersistentManifold.h"
//quick hack, we need internals, not just the public ode api
#include <../ode/src/collision_kernel.h>
#include "CollisionShapes/BoxShape.h"
#include "BulletOdeCollide.h"
#include "CollisionShapes/SphereShape.h"
#include "CollisionShapes/CylinderShape.h"
#include "CollisionShapes/MultiSphereShape.h"//capped cylinder is convex hull of two spheres
#include "CollisionShapes/ConvexTriangleCallback.h"
#include "BVHTrimeshShape.h"
#include "NarrowPhaseCollision/GjkPairDetector.h"
#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
#include "NarrowPhaseCollision/MinkowskiPenetrationDepthSolver.h"
///for comparison/unit testing
#ifdef UNIT_TEST_COMPARE_PENETRATION_DEPTH
#include "../ExtraSolid35/Solid3EpaPenetrationDepth.h"
#endif //UNIT_TEST_COMPARE_PENETRATION_DEPTH
#include "BulletOdeManifoldResult.h"
#include "BulletOdeTransformConvert.h"
BulletOdeCollisionPair::BulletOdeCollisionPair(dGeomID o1,dGeomID o2)
{
m_manifold = new PersistentManifold();
m_o1 = o1;
m_o2 = o2;
m_shape1 = CreateShapeFromGeom(o1);
m_shape2 = CreateShapeFromGeom(o2);
}
BulletOdeCollisionPair::~BulletOdeCollisionPair()
{
}
void BulletOdeCollisionPair::CalculateContacts()
{
//perform gjk, passing the points to the persistent manifold and convert to ode contacts
if ((!m_shape1) || (!m_shape2))
return;
if (m_shape1->IsConcave() && m_shape2->IsConvex())
{
TriangleMeshShape* triangleMesh = (TriangleMeshShape*)m_shape1;
ConvexShape* convexShape2 = (ConvexShape*)m_shape2;
float collisionMarginTriangle = 0.02f;//triangleMesh->GetMargin();
SimdTransform triangleMeshTrans = GetTransformFromGeom(m_o1);
SimdTransform convexTrans = GetTransformFromGeom(m_o2);
ConvexTriangleCallback convexTriangleCallback(m_manifold,convexShape2,convexTrans,triangleMeshTrans);
convexTriangleCallback.Update(collisionMarginTriangle);
triangleMesh->ProcessAllTriangles( &convexTriangleCallback,convexTriangleCallback.GetAabbMin(),convexTriangleCallback.GetAabbMax());
m_manifold->RefreshContactPoints(triangleMeshTrans,convexTrans);
}
if (m_shape1->IsConvex() && m_shape2->IsConvex())
{
ConvexShape* convexShape1 = (ConvexShape*)m_shape1;
ConvexShape* convexShape2 = (ConvexShape*)m_shape2;
BulletOdeManifoldResult output(m_o1,m_o2,m_manifold);
GjkPairDetector::ClosestPointInput input;
VoronoiSimplexSolver simplexSolver;
#ifdef UNIT_TEST_COMPARE_PENETRATION_DEPTH
Solid3EpaPenetrationDepth penetrationDepthSolver;
#else
MinkowskiPenetrationDepthSolver penetrationDepthSolver;
#endif// UNIT_TEST_COMPARE_PENETRATION_DEPTH
GjkPairDetector gjkDetector(convexShape1,convexShape2,&simplexSolver,&penetrationDepthSolver);
gjkDetector.SetMinkowskiA(convexShape1);
gjkDetector.SetMinkowskiB(convexShape2);
input.m_maximumDistanceSquared = m_shape1->GetMargin()+ m_shape2->GetMargin() + m_manifold->GetManifoldMargin();
input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared;
input.m_maximumDistanceSquared = 1e30;//?
input.m_transformA = GetTransformFromGeom(m_o1);
input.m_transformB = GetTransformFromGeom(m_o2);
gjkDetector.GetClosestPoints(input,output,0);
m_manifold->RefreshContactPoints(input.m_transformA,input.m_transformB);
}
}
void BulletOdeCollisionPair::ProcessCollision (BroadphaseProxy* proxy0,BroadphaseProxy* proxy1,const struct DispatcherInfo& dispatchInfo)
{
}
float BulletOdeCollisionPair::CalculateTimeOfImpact(BroadphaseProxy* proxy0,BroadphaseProxy* proxy1,const struct DispatcherInfo& dispatchInfo)
{
return 1.f;
}
CollisionShape* BulletOdeCollisionPair::CreateShapeFromGeom(dGeomID geom)
{
CollisionShape* shape = 0;
if (geom->type == dConvexClass)
{
shape = GetCollisionShapeFromConvex(geom);
} else
{
//bullet shape versus ode geom, create a compatible shape from the ode types
switch (geom->type)
{
case dPlaneClass:
break;
case dBoxClass:
{
dVector3 size;
dGeomBoxGetLengths (geom,size);
SimdVector3 halfExtents(0.5f*size[0],0.5f*size[1],0.5f*size[2]);
shape = new BoxShape(halfExtents);
break;
}
case dSphereClass:
{
dVector3 size;
shape = new SphereShape(dGeomSphereGetRadius(geom));
break;
}
case dCylinderClass:
{
dVector3 size;
dGeomBoxGetLengths (geom,size);
SimdVector3 boxHalfExtents(size[0],size[0],size[1]);
shape = new CylinderShapeZ(boxHalfExtents);
break;
}
case dCCylinderClass:
{
dReal radius,length;
dGeomCCylinderGetParams (geom, &radius, &length);
SimdVector3 boxHalfExtents(radius,radius,0.5f*length);
int numspheres = 2;
SimdVector3 centers[2]={ SimdVector3(0,0,0.5f*length),SimdVector3(0,0,-0.5f*length)};
SimdScalar radi[2]={radius,radius};
shape = new MultiSphereShape(boxHalfExtents,centers,radi,numspheres);
break;
}
case dTriMeshClass:
{
dxTriMesh* trimesh = (dxTriMesh*) geom;
shape = 0;//new BVHTrimeshShape(trimesh);
break;
}
default:
{
}
};
}
return shape;
}

View File

@@ -0,0 +1,35 @@
#ifndef BULLET_ODE_COLLISION_PAIR_H
#define BULLET_ODE_COLLISION_PAIR_H
#include <BroadphaseCollision/CollisionAlgorithm.h>
#include <ode/common.h>
class PersistentManifold;
/// BulletOdeCollisionPair provides Bullet convex collision detection for Open Dynamics Engine
class BulletOdeCollisionPair : public CollisionAlgorithm
{
public:
BulletOdeCollisionPair(dGeomID o1,dGeomID o2);
virtual ~BulletOdeCollisionPair();
PersistentManifold* m_manifold;
dGeomID m_o1;
dGeomID m_o2;
class CollisionShape* m_shape1;
class CollisionShape* m_shape2;
void CalculateContacts();
CollisionShape* CreateShapeFromGeom(dGeomID);
///future support for Bullet broadphase + framework?
virtual void ProcessCollision (BroadphaseProxy* proxy0,BroadphaseProxy* proxy1,const struct DispatcherInfo& dispatchInfo);
///future support for Bullet broadphase + framework?
virtual float CalculateTimeOfImpact(BroadphaseProxy* proxy0,BroadphaseProxy* proxy1,const struct DispatcherInfo& dispatchInfo);
};
#endif //BULLET_ODE_COLLISION_PAIR_H

View File

@@ -0,0 +1,33 @@
#include "BulletOdeManifoldResult.h"
#include "NarrowPhaseCollision/PersistentManifold.h"
#include "BulletOdeTransformConvert.h"
BulletOdeManifoldResult::BulletOdeManifoldResult(dGeomID geom1,dGeomID geom2,PersistentManifold* manifoldPtr)
:m_manifoldPtr(manifoldPtr),
m_geom1(geom1),
m_geom2(geom2)
{
}
void BulletOdeManifoldResult::AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)
{
if (depth > m_manifoldPtr->GetManifoldMargin())
return;
SimdTransform transAInv = GetTransformFromGeom(m_geom1).inverse();
SimdTransform transBInv = GetTransformFromGeom(m_geom2).inverse();
SimdVector3 pointA = pointInWorld + normalOnBInWorld * depth;
SimdVector3 localA = transAInv(pointA );
SimdVector3 localB = transBInv(pointInWorld);
ManifoldPoint newPt(localA,localB,normalOnBInWorld,depth);
int insertIndex = m_manifoldPtr->GetCacheEntry(newPt);
if (insertIndex >= 0)
{
m_manifoldPtr->ReplaceContactPoint(newPt,insertIndex);
} else
{
m_manifoldPtr->AddManifoldPoint(newPt);
}
}

View File

@@ -0,0 +1,38 @@
/*
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 BULLET_ODE_MANIFOLD_RESULT_H
#define BULLET_ODE_MANIFOLD_RESULT_H
#include "NarrowPhaseCollision/DiscreteCollisionDetectorInterface.h"
class PersistentManifold;
#include <ode/common.h>
class BulletOdeManifoldResult : public DiscreteCollisionDetectorInterface::Result
{
PersistentManifold* m_manifoldPtr;
dGeomID m_geom1;
dGeomID m_geom2;
public:
BulletOdeManifoldResult(dGeomID geom1,dGeomID geom2,PersistentManifold* manifoldPtr);
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth);
};
#endif //BULLET_ODE_MANIFOLD_RESULT_H

View File

@@ -0,0 +1,39 @@
#include "BulletOdeTransformConvert.h"
#include "../ode/src/collision_kernel.h"
SimdTransform GetTransformFromGeom(dGeomID geom)
{
SimdTransform trans;
trans.setIdentity();
const dReal* pos = dGeomGetPosition (geom);// pointer to object's position vector
const dReal* rot = dGeomGetRotation (geom);; // pointer to object's rotation matrix, 4*3 format!
SimdMatrix3x3 orn(rot[0],rot[1],rot[2],
rot[4],rot[5],rot[6],
rot[8],rot[9],rot[10]);
trans.setOrigin(SimdVector3(pos[0],pos[1],pos[2]));
trans.setBasis(orn);
return trans;
}
SimdTransform GetTransformFromBody(dBodyID body)
{
SimdTransform trans;
const dReal* pos = body->pos;
const dReal* rot = body->R;
SimdMatrix3x3 orn(rot[0],rot[1],rot[2],
rot[4],rot[5],rot[6],
rot[8],rot[9],rot[10]);
trans.setOrigin(SimdVector3(pos[0],pos[1],pos[2]));
trans.setBasis(orn);
return trans;
}

View File

@@ -0,0 +1,10 @@
#ifndef BULLET_ODE_TRANSFORM_CONVERT_H
#define BULLET_ODE_TRANSFORM_CONVERT_H
#include "SimdTransform.h"
#include <ode/common.h>
SimdTransform GetTransformFromGeom(dGeomID geom);
SimdTransform GetTransformFromBody(dBodyID body);
#endif //BULLET_ODE_TRANSFORM_CONVERT_H

View File

@@ -0,0 +1,70 @@
#include "CollisionShapes/SphereShape.h"
#include "CollisionShapes/CylinderShape.h"
#include "CollisionShapes/MultiSphereShape.h"//capped cylinder is convex hull of two spheres
#include "CollisionShapes/ConvexTriangleCallback.h"
#include "CollisionShapes/BoxShape.h"
//need access to internals to convert...
#include <../ode/src/collision_kernel.h>
CollisionShape* CreateShapeFromGeom(dGeomID geom)
{
CollisionShape* shape = 0;
switch (geom->type)
{
case dPlaneClass:
break;
case dBoxClass:
{
dVector3 size;
dGeomBoxGetLengths (geom,size);
SimdVector3 halfExtents(0.5f*size[0],0.5f*size[1],0.5f*size[2]);
shape = new BoxShape(halfExtents);
break;
}
case dSphereClass:
{
dVector3 size;
shape = new SphereShape(dGeomSphereGetRadius(geom));
break;
}
case dCylinderClass:
{
dVector3 size;
dGeomBoxGetLengths (geom,size);
SimdVector3 boxHalfExtents(size[0],size[0],size[1]);
shape = new CylinderShapeZ(boxHalfExtents);
break;
}
case dCCylinderClass:
{
dReal radius,length;
dGeomCCylinderGetParams (geom, &radius, &length);
SimdVector3 boxHalfExtents(radius,radius,0.5f*length);
int numspheres = 2;
SimdVector3 centers[2]={ SimdVector3(0,0,0.5f*length),SimdVector3(0,0,-0.5f*length)};
SimdScalar radi[2]={radius,radius};
shape = new MultiSphereShape(boxHalfExtents,centers,radi,numspheres);
break;
}
/*case dTriMeshClass:
{
dxTriMesh* trimesh = (dxTriMesh*) geom;
shape = 0;//new BVHTrimeshShape(trimesh);
break;
}
*/
default:
{
}
};
return shape;
}

View File

@@ -0,0 +1,11 @@
#ifndef GEOM_TO_SHAPE_H
#define GEOM_TO_SHAPE_H
class CollisionShape;
//need internals to handle dGeomID
#include <../ode/src/collision_kernel.h>
CollisionShape* CreateShapeFromGeom(dGeomID geom);
#endif //

View File

@@ -0,0 +1,119 @@
? OPCODE/Debug
? OPCODE/Opcode.vcproj
? OPCODE/Release
? VC6/Debug
? VC6/Release
? VC6/msvcdefs.def
? VC6/ode.ncb
? VC6/ode.vcproj
? VC6/Samples/BuildLog.htm
? VC6/Samples/DrawStuff.vcproj
? VC6/Samples/DrawStuff_Debug
? VC6/Samples/DrawStuff_Release
? VC6/Samples/MakeAllTests.ncb
? VC6/Samples/MakeAllTests.sln
? VC6/Samples/MakeAllTests.suo
? VC6/Samples/MakeAllTests.vcproj
? VC6/Samples/Test_BoxStack.vcproj
? VC6/Samples/Test_BoxStack_Debug
? VC6/Samples/Test_BoxStack_Release
? VC6/Samples/Test_Buggy.vcproj
? VC6/Samples/Test_Chain1.vcproj
? VC6/Samples/Test_Chain2.vcproj
? VC6/Samples/Test_Collision.vcproj
? VC6/Samples/Test_Friction.vcproj
? VC6/Samples/Test_Hinge.vcproj
? VC6/Samples/Test_I.vcproj
? VC6/Samples/Test_Joints.vcproj
? VC6/Samples/Test_MovingTrimesh.vcproj
? VC6/Samples/Test_Ode.vcproj
? VC6/Samples/Test_Slider.vcproj
? VC6/Samples/Test_Space.vcproj
? VC6/Samples/Test_Step.vcproj
? VC6/Samples/Test_Trimesh.vcproj
? VC6/Samples/Test_Trimesh_Debug
? VC6/Samples/Test_Trimesh_Release
? VC6/Samples/state.dif
? include/ode/config.h
? ode/test/test_trimesh_convex.cpp
? ode/test/text_convex.cpp
Index: include/ode/collision.h
===================================================================
RCS file: /cvsroot/opende/ode/include/ode/collision.h,v
retrieving revision 1.9
diff -u -r1.9 collision.h
--- include/ode/collision.h 19 Jun 2004 15:44:22 -0000 1.9
+++ include/ode/collision.h 6 Nov 2005 23:06:52 -0000
@@ -84,6 +84,7 @@
dRayClass,
dGeomTransformClass,
dTriMeshClass,
+ dConvexClass,
dFirstSpaceClass,
dSimpleSpaceClass = dFirstSpaceClass,
Index: ode/src/collision_kernel.cpp
===================================================================
RCS file: /cvsroot/opende/ode/ode/src/collision_kernel.cpp,v
retrieving revision 1.18
diff -u -r1.18 collision_kernel.cpp
--- ode/src/collision_kernel.cpp 19 Apr 2004 18:27:56 -0000 1.18
+++ ode/src/collision_kernel.cpp 6 Nov 2005 23:10:02 -0000
@@ -146,6 +146,17 @@
setCollider (dTriMeshClass,dTriMeshClass,&dCollideTTL);
setCollider (dTriMeshClass,dCCylinderClass,&dCollideCCTL);
#endif
+
+#ifdef BULLET_CONVEX_SUPPORT
+ ///see collision_convex.cpp
+ setCollider (dConvexClass,dConvexClass,&dCollideConvexConvex);
+ setCollider (dConvexClass,dPlaneClass,&dCollideConvexConvex);
+ setCollider (dConvexClass,dBoxClass,&dCollideConvexConvex);
+ setCollider (dConvexClass,dSphereClass,&dCollideConvexConvex);
+ setCollider (dConvexClass,dCCylinderClass,&dCollideConvexConvex);
+ setCollider( dTriMeshClass,dConvexClass, dCollideConvexConvex);
+#endif //BULLET_CONVEX_SUPPORT
+
setAllColliders (dGeomTransformClass,&dCollideTransform);
}
Index: ode/src/collision_std.h
===================================================================
RCS file: /cvsroot/opende/ode/ode/src/collision_std.h,v
retrieving revision 1.2
diff -u -r1.2 collision_std.h
--- ode/src/collision_std.h 1 Dec 2002 06:13:42 -0000 1.2
+++ ode/src/collision_std.h 6 Nov 2005 23:03:52 -0000
@@ -37,6 +37,7 @@
// the same interface as dCollide(). the first and second geom arguments must
// have the specified types.
+
int dCollideSphereSphere (dxGeom *o1, dxGeom *o2, int flags,
dContactGeom *contact, int skip);
int dCollideSphereBox (dxGeom *o1, dxGeom *o2, int flags,
@@ -63,6 +64,9 @@
int flags, dContactGeom *contact, int skip);
int dCollideRayPlane (dxGeom *o1, dxGeom *o2, int flags,
dContactGeom *contact, int skip);
+///dCollideConvexConvex: see collision_convex.cpp for details
+int dCollideConvexConvex(dxGeom *o1, dxGeom *o2, int flags,
+ dContactGeom *contact, int skip);
#endif
Index: ode/src/collision_trimesh_internal.h
===================================================================
RCS file: /cvsroot/opende/ode/ode/src/collision_trimesh_internal.h,v
retrieving revision 1.10
diff -u -r1.10 collision_trimesh_internal.h
--- ode/src/collision_trimesh_internal.h 21 Sep 2004 20:54:21 -0000 1.10
+++ ode/src/collision_trimesh_internal.h 6 Nov 2005 23:04:52 -0000
@@ -25,6 +25,7 @@
#ifndef _ODE_COLLISION_TRIMESH_INTERNAL_H_
#define _ODE_COLLISION_TRIMESH_INTERNAL_H_
+int dCollideTrimeshConvex(dxGeom* g1, dxGeom* cnvx, int Flags, dContactGeom* Contacts, int Stride);
int dCollideSTL(dxGeom *o1, dxGeom *o2, int flags, dContactGeom *contact, int skip);
int dCollideBTL(dxGeom *o1, dxGeom *o2, int flags, dContactGeom *contact, int skip);
int dCollideRTL(dxGeom *o1, dxGeom *o2, int flags, dContactGeom *contact, int skip);