mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 13:50:04 +00:00
Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
commit
1c5e5d2b3f
@ -1,5 +1,5 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<robot name="cube">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
|
@ -1,5 +1,5 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<robot name="plane">
|
||||
<link name="planeLink">
|
||||
<contact>
|
||||
<lateral_friction value="1"/>
|
||||
|
@ -871,6 +871,16 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
||||
|
||||
int width = 1024;
|
||||
int height=768;
|
||||
|
||||
if (args.CheckCmdLineFlag("width"))
|
||||
{
|
||||
args.GetCmdLineArgument("width",width );
|
||||
}
|
||||
if (args.CheckCmdLineFlag("height"))
|
||||
{
|
||||
args.GetCmdLineArgument("height",height);
|
||||
}
|
||||
|
||||
#ifndef NO_OPENGL3
|
||||
SimpleOpenGL3App* simpleApp=0;
|
||||
sUseOpenGL2 =args.CheckCmdLineFlag("opengl2");
|
||||
|
@ -1026,6 +1026,11 @@ struct BulletMJCFImporterInternalData
|
||||
{
|
||||
handled = true;
|
||||
}
|
||||
if (n=="site")
|
||||
{
|
||||
handled = true;
|
||||
}
|
||||
|
||||
if (!handled)
|
||||
{
|
||||
logger->reportWarning( (sourceFileLocation(xml) + ": unknown field '" + n + "'").c_str() );
|
||||
@ -1323,6 +1328,11 @@ int BulletMJCFImporter::getRootLinkIndex() const
|
||||
return "";
|
||||
}
|
||||
|
||||
std::string BulletMJCFImporter::getBodyName() const
|
||||
{
|
||||
return m_data->m_fileModelName;
|
||||
}
|
||||
|
||||
bool BulletMJCFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
{
|
||||
// UrdfLink* link = m_data->getLink(linkIndex);
|
||||
|
@ -42,6 +42,8 @@ public:
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
virtual std::string getBodyName() const;
|
||||
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
|
@ -270,6 +270,11 @@ std::string BulletURDFImporter::getLinkName(int linkIndex) const
|
||||
return "";
|
||||
}
|
||||
|
||||
std::string BulletURDFImporter::getBodyName() const
|
||||
{
|
||||
return m_data->m_urdfParser.getModel().m_name;
|
||||
}
|
||||
|
||||
std::string BulletURDFImporter::getJointName(int linkIndex) const
|
||||
{
|
||||
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex);
|
||||
@ -956,10 +961,16 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case URDF_GEOM_PLANE:
|
||||
{
|
||||
b3Warning("No default visual for URDF_GEOM_PLANE");
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
b3Warning("Error: unknown visual geometry type %i\n", visual->m_geometry.m_type);
|
||||
}
|
||||
}
|
||||
|
||||
//if we have a convex, tesselate into localVertices/localIndices
|
||||
if ((glmesh==0) && convexColShape)
|
||||
|
@ -35,6 +35,8 @@ public:
|
||||
|
||||
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
||||
|
||||
virtual std::string getBodyName() const;
|
||||
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
@ -15,7 +15,6 @@ public:
|
||||
|
||||
virtual ~URDFImporterInterface() {}
|
||||
|
||||
|
||||
virtual bool loadURDF(const char* fileName, bool forceFixedBase = false)=0;
|
||||
|
||||
virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false;}
|
||||
@ -27,6 +26,13 @@ public:
|
||||
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const =0;
|
||||
|
||||
//various derived class in internal source code break with new pure virtual methods, so provide some default implementation
|
||||
virtual std::string getBodyName() const
|
||||
{
|
||||
return "";
|
||||
}
|
||||
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const { return false;}
|
||||
|
||||
|
@ -552,7 +552,6 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
@ -20,6 +20,7 @@ struct BodyJointInfoCache
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
struct PhysicsClientSharedMemoryInternalData {
|
||||
@ -106,6 +107,7 @@ bool PhysicsClientSharedMemory::getBodyInfo(int bodyUniqueId, struct b3BodyInfo&
|
||||
{
|
||||
BodyJointInfoCache* bodyJoints = *bodyJointsPtr;
|
||||
info.m_baseName = bodyJoints->m_baseName.c_str();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -306,6 +308,7 @@ void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const Sha
|
||||
|
||||
BodyJointInfoCache* bodyJoints = new BodyJointInfoCache;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -418,6 +421,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
|
||||
BodyJointInfoCache* bodyJoints = new BodyJointInfoCache;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++) {
|
||||
|
||||
|
@ -17,6 +17,7 @@ struct BodyJointInfoCache2
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
|
||||
@ -605,6 +606,7 @@ void PhysicsDirect::processBodyJointInfo(int bodyUniqueId, const SharedMemorySta
|
||||
|
||||
BodyJointInfoCache2* bodyJoints = new BodyJointInfoCache2;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -931,6 +933,7 @@ bool PhysicsDirect::getBodyInfo(int bodyUniqueId, struct b3BodyInfo& info) const
|
||||
{
|
||||
BodyJointInfoCache2* bodyJoints = *bodyJointsPtr;
|
||||
info.m_baseName = bodyJoints->m_baseName.c_str();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -120,6 +120,7 @@ struct InteralBodyData
|
||||
btMultiBody* m_multiBody;
|
||||
btRigidBody* m_rigidBody;
|
||||
int m_testData;
|
||||
std::string m_bodyName;
|
||||
|
||||
btTransform m_rootLocalInertialFrame;
|
||||
btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
|
||||
@ -1579,6 +1580,7 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
|
||||
{
|
||||
btScalar mass = 0;
|
||||
bodyHandle->m_rootLocalInertialFrame.setIdentity();
|
||||
bodyHandle->m_bodyName = u2b.getBodyName();
|
||||
btVector3 localInertiaDiagonal(0,0,0);
|
||||
int urdfLinkIndex = u2b.getRootLinkIndex();
|
||||
u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
|
||||
@ -1797,6 +1799,8 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
btMultiBody* mb = creation.getBulletMultiBody();
|
||||
btRigidBody* rb = creation.getRigidBody();
|
||||
|
||||
bodyHandle->m_bodyName = u2b.getBodyName();
|
||||
|
||||
if (useMultiBody)
|
||||
{
|
||||
|
||||
@ -2525,6 +2529,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED;
|
||||
serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId;
|
||||
serverStatusOut.m_dataStreamArguments.m_bodyName[0] = 0;
|
||||
|
||||
InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateJacobianArguments.m_bodyUniqueId);
|
||||
if (bodyHandle)
|
||||
{
|
||||
strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName,bodyHandle->m_bodyName.c_str());
|
||||
}
|
||||
|
||||
serverStatusOut.m_numDataStreamBytes = streamSizeInBytes;
|
||||
|
||||
hasStatus = true;
|
||||
@ -2852,6 +2864,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverStatusOut.m_numDataStreamBytes = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize();
|
||||
}
|
||||
serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId;
|
||||
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
|
||||
strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName, body->m_bodyName.c_str());
|
||||
hasStatus = true;
|
||||
|
||||
} else
|
||||
@ -5217,8 +5231,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
default:
|
||||
{
|
||||
BT_PROFILE("CMD_UNKNOWN");
|
||||
|
@ -103,6 +103,7 @@ struct BulletDataStreamArgs
|
||||
{
|
||||
char m_bulletFileName[MAX_FILENAME_LENGTH];
|
||||
int m_bodyUniqueId;
|
||||
char m_bodyName[MAX_FILENAME_LENGTH];
|
||||
};
|
||||
|
||||
struct SetJointFeedbackArgs
|
||||
@ -364,9 +365,6 @@ struct RequestActualStateArgs
|
||||
int m_bodyUniqueId;
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
struct SendActualStateArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
|
@ -201,6 +201,7 @@ struct b3UserConstraint
|
||||
struct b3BodyInfo
|
||||
{
|
||||
const char* m_baseName;
|
||||
const char* m_bodyName; // for btRigidBody, it does not have a base, but can still have a body name from urdf
|
||||
};
|
||||
|
||||
|
||||
|
@ -49,6 +49,9 @@ trailDuration = 15
|
||||
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT,"LOG0001.txt",[0,1,2])
|
||||
|
||||
for i in xrange(5):
|
||||
print "Body %d's name is %s." % (i, p.getBodyInfo(i)[1])
|
||||
|
||||
while 1:
|
||||
if (useRealTimeSimulation):
|
||||
dt = datetime.now()
|
||||
|
@ -221,6 +221,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
int freeIndex = -1;
|
||||
int method = eCONNECT_GUI;
|
||||
int i;
|
||||
char* options="";
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
if (sNumPhysicsClients >= MAX_PHYSICS_CLIENTS)
|
||||
@ -237,15 +238,24 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
|
||||
const char* hostName = "localhost";
|
||||
|
||||
int size = PySequence_Size(args);
|
||||
if (size == 1)
|
||||
|
||||
static char* kwlist1[] = {"method","key", "options", NULL};
|
||||
static char* kwlist2[] = {"method","hostName", "port", "options", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|is", kwlist1, &method,&key,&options))
|
||||
{
|
||||
if (!PyArg_ParseTuple(args, "i", &method))
|
||||
int port = -1;
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sis", kwlist2, &method,&hostName, &port,&options))
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"connectPhysicsServer expected argument GUI, "
|
||||
"DIRECT, SHARED_MEMORY, UDP or TCP");
|
||||
return NULL;
|
||||
} else
|
||||
{
|
||||
PyErr_Clear();
|
||||
if (port>=0)
|
||||
{
|
||||
udpPort = port;
|
||||
tcpPort = port;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -264,45 +274,12 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
}
|
||||
}
|
||||
|
||||
if (size == 2)
|
||||
{
|
||||
if (!PyArg_ParseTuple(args, "ii", &method, &key))
|
||||
{
|
||||
if (!PyArg_ParseTuple(args, "is", &method, &hostName))
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"connectPhysicsServer cannot parse second argument (either integer or string)");
|
||||
return NULL;
|
||||
}
|
||||
else
|
||||
{
|
||||
PyErr_Clear();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (size == 3)
|
||||
{
|
||||
int port = -1;
|
||||
if (!PyArg_ParseTuple(args, "isi", &method, &hostName, &port))
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"connectPhysicsServer 3 arguments: method, hostname, port");
|
||||
return NULL;
|
||||
}
|
||||
if (port >= 0)
|
||||
{
|
||||
udpPort = port;
|
||||
tcpPort = port;
|
||||
}
|
||||
}
|
||||
|
||||
switch (method)
|
||||
{
|
||||
case eCONNECT_GUI:
|
||||
{
|
||||
int argc = 0;
|
||||
char* argv[1] = {0};
|
||||
int argc = 2;
|
||||
char* argv[2] = {"unused",options};
|
||||
|
||||
#ifdef __APPLE__
|
||||
sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
|
||||
@ -1714,8 +1691,9 @@ static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject*
|
||||
struct b3BodyInfo info;
|
||||
if (b3GetBodyInfo(sm, bodyUniqueId, &info))
|
||||
{
|
||||
PyObject* pyListJointInfo = PyTuple_New(1);
|
||||
PyObject* pyListJointInfo = PyTuple_New(2);
|
||||
PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName));
|
||||
PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString(info.m_bodyName));
|
||||
return pyListJointInfo;
|
||||
}
|
||||
}
|
||||
|
@ -562,7 +562,7 @@ void b3GpuJacobiContactSolver::solveGroupHost(b3RigidBodyData* bodies,b3InertiaD
|
||||
b3AlignedObjectArray<b3Vector3> deltaAngularVelocities;
|
||||
deltaLinearVelocities.resize(totalNumSplitBodies);
|
||||
deltaAngularVelocities.resize(totalNumSplitBodies);
|
||||
for (int i=0;i<totalNumSplitBodies;i++)
|
||||
for (unsigned int i=0;i<totalNumSplitBodies;i++)
|
||||
{
|
||||
deltaLinearVelocities[i].setZero();
|
||||
deltaAngularVelocities[i].setZero();
|
||||
|
File diff suppressed because it is too large
Load Diff
1022
src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h
Normal file
1022
src/BulletCollision/BroadphaseCollision/btAxisSweep3Internal.h
Normal file
File diff suppressed because it is too large
Load Diff
@ -41,6 +41,10 @@ struct btBroadphaseRayCallback : public btBroadphaseAabbCallback
|
||||
btScalar m_lambda_max;
|
||||
|
||||
virtual ~btBroadphaseRayCallback() {}
|
||||
|
||||
protected:
|
||||
|
||||
btBroadphaseRayCallback() {}
|
||||
};
|
||||
|
||||
#include "LinearMath/btVector3.h"
|
||||
|
@ -15,3 +15,4 @@ subject to the following restrictions:
|
||||
|
||||
#include "btBroadphaseProxy.h"
|
||||
|
||||
BT_NOT_EMPTY_FILE // fix warning LNK4221: This object file does not define any previously undefined public symbols, so it will not be used by any link operation that consumes this library
|
||||
|
@ -23,6 +23,9 @@ struct btBroadphasePair;
|
||||
///The btOverlappingPairCallback class is an additional optional broadphase user callback for adding/removing overlapping pairs, similar interface to btOverlappingPairCache.
|
||||
class btOverlappingPairCallback
|
||||
{
|
||||
protected:
|
||||
btOverlappingPairCallback() {}
|
||||
|
||||
public:
|
||||
virtual ~btOverlappingPairCallback()
|
||||
{
|
||||
|
@ -102,6 +102,7 @@ SET(Root_HDRS
|
||||
../btBulletCollisionCommon.h
|
||||
)
|
||||
SET(BroadphaseCollision_HDRS
|
||||
BroadphaseCollision/btAxisSweep3Internal.h
|
||||
BroadphaseCollision/btAxisSweep3.h
|
||||
BroadphaseCollision/btBroadphaseInterface.h
|
||||
BroadphaseCollision/btBroadphaseProxy.h
|
||||
@ -189,12 +190,15 @@ SET(CollisionShapes_HDRS
|
||||
SET(Gimpact_HDRS
|
||||
Gimpact/btBoxCollision.h
|
||||
Gimpact/btClipPolygon.h
|
||||
Gimpact/btContactProcessingStructs.h
|
||||
Gimpact/btContactProcessing.h
|
||||
Gimpact/btGenericPoolAllocator.h
|
||||
Gimpact/btGeometryOperations.h
|
||||
Gimpact/btGImpactBvhStructs.h
|
||||
Gimpact/btGImpactBvh.h
|
||||
Gimpact/btGImpactCollisionAlgorithm.h
|
||||
Gimpact/btGImpactMassUtil.h
|
||||
Gimpact/btGImpactQuantizedBvhStructs.h
|
||||
Gimpact/btGImpactQuantizedBvh.h
|
||||
Gimpact/btGImpactShape.h
|
||||
Gimpact/btQuantization.h
|
||||
|
@ -24,12 +24,13 @@ class btActivatingCollisionAlgorithm : public btCollisionAlgorithm
|
||||
// btCollisionObject* m_colObj0;
|
||||
// btCollisionObject* m_colObj1;
|
||||
|
||||
public:
|
||||
protected:
|
||||
|
||||
btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci);
|
||||
|
||||
btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap);
|
||||
|
||||
public:
|
||||
virtual ~btActivatingCollisionAlgorithm();
|
||||
|
||||
};
|
||||
|
@ -33,8 +33,6 @@ class btDispatcher;
|
||||
class btCollisionObject;
|
||||
|
||||
class btCollisionShape;
|
||||
typedef bool (*btShapePairCallback)(const btCollisionShape* pShape0, const btCollisionShape* pShape1);
|
||||
extern btShapePairCallback gCompoundCompoundChildShapePairCallback;
|
||||
|
||||
/// btCompoundCompoundCollisionAlgorithm supports collision between two btCompoundCollisionShape shapes
|
||||
class btCompoundCompoundCollisionAlgorithm : public btCompoundCollisionAlgorithm
|
||||
|
@ -111,6 +111,7 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
|
||||
return;
|
||||
|
||||
bool isSwapped = m_manifoldPtr->getBody0() != m_body0Wrap->getCollisionObject();
|
||||
bool isNewCollision = m_manifoldPtr->getNumContacts() == 0;
|
||||
|
||||
btVector3 pointA = pointInWorld + normalOnBInWorld * depth;
|
||||
|
||||
@ -193,5 +194,9 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
|
||||
(*gContactAddedCallback)(m_manifoldPtr->getContactPoint(insertIndex),obj0Wrap,newPt.m_partId0,newPt.m_index0,obj1Wrap,newPt.m_partId1,newPt.m_index1);
|
||||
}
|
||||
|
||||
if (gContactStartedCallback && isNewCollision)
|
||||
{
|
||||
gContactStartedCallback(m_manifoldPtr);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -93,10 +93,12 @@ protected:
|
||||
aabbMax = m_localAabbMax;
|
||||
}
|
||||
|
||||
public:
|
||||
protected:
|
||||
|
||||
btPolyhedralConvexAabbCachingShape();
|
||||
|
||||
public:
|
||||
|
||||
inline void getNonvirtualAabb(const btTransform& trans,btVector3& aabbMin,btVector3& aabbMax, btScalar margin) const
|
||||
{
|
||||
|
||||
|
@ -27,86 +27,7 @@ subject to the following restrictions:
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "btTriangleShapeEx.h"
|
||||
|
||||
|
||||
|
||||
/**
|
||||
Configuration var for applying interpolation of contact normals
|
||||
*/
|
||||
#define NORMAL_CONTACT_AVERAGE 1
|
||||
|
||||
#define CONTACT_DIFF_EPSILON 0.00001f
|
||||
|
||||
///The GIM_CONTACT is an internal GIMPACT structure, similar to btManifoldPoint.
|
||||
///@todo: remove and replace GIM_CONTACT by btManifoldPoint.
|
||||
class GIM_CONTACT
|
||||
{
|
||||
public:
|
||||
btVector3 m_point;
|
||||
btVector3 m_normal;
|
||||
btScalar m_depth;//Positive value indicates interpenetration
|
||||
btScalar m_distance;//Padding not for use
|
||||
int m_feature1;//Face number
|
||||
int m_feature2;//Face number
|
||||
public:
|
||||
GIM_CONTACT()
|
||||
{
|
||||
}
|
||||
|
||||
GIM_CONTACT(const GIM_CONTACT & contact):
|
||||
m_point(contact.m_point),
|
||||
m_normal(contact.m_normal),
|
||||
m_depth(contact.m_depth),
|
||||
m_feature1(contact.m_feature1),
|
||||
m_feature2(contact.m_feature2)
|
||||
{
|
||||
}
|
||||
|
||||
GIM_CONTACT(const btVector3 &point,const btVector3 & normal,
|
||||
btScalar depth, int feature1, int feature2):
|
||||
m_point(point),
|
||||
m_normal(normal),
|
||||
m_depth(depth),
|
||||
m_feature1(feature1),
|
||||
m_feature2(feature2)
|
||||
{
|
||||
}
|
||||
|
||||
//! Calcs key for coord classification
|
||||
SIMD_FORCE_INLINE unsigned int calc_key_contact() const
|
||||
{
|
||||
int _coords[] = {
|
||||
(int)(m_point[0]*1000.0f+1.0f),
|
||||
(int)(m_point[1]*1333.0f),
|
||||
(int)(m_point[2]*2133.0f+3.0f)};
|
||||
unsigned int _hash=0;
|
||||
unsigned int *_uitmp = (unsigned int *)(&_coords[0]);
|
||||
_hash = *_uitmp;
|
||||
_uitmp++;
|
||||
_hash += (*_uitmp)<<4;
|
||||
_uitmp++;
|
||||
_hash += (*_uitmp)<<8;
|
||||
return _hash;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void interpolate_normals( btVector3 * normals,int normal_count)
|
||||
{
|
||||
btVector3 vec_sum(m_normal);
|
||||
for(int i=0;i<normal_count;i++)
|
||||
{
|
||||
vec_sum += normals[i];
|
||||
}
|
||||
|
||||
btScalar vec_sum_len = vec_sum.length2();
|
||||
if(vec_sum_len <CONTACT_DIFF_EPSILON) return;
|
||||
|
||||
//GIM_INV_SQRT(vec_sum_len,vec_sum_len); // 1/sqrt(vec_sum_len)
|
||||
|
||||
m_normal = vec_sum/btSqrt(vec_sum_len);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#include "btContactProcessingStructs.h"
|
||||
|
||||
class btContactArray:public btAlignedObjectArray<GIM_CONTACT>
|
||||
{
|
||||
@ -141,5 +62,4 @@ public:
|
||||
void merge_contacts_unique(const btContactArray & contacts);
|
||||
};
|
||||
|
||||
|
||||
#endif // GIM_CONTACT_H_INCLUDED
|
||||
|
109
src/BulletCollision/Gimpact/btContactProcessingStructs.h
Normal file
109
src/BulletCollision/Gimpact/btContactProcessingStructs.h
Normal file
@ -0,0 +1,109 @@
|
||||
#ifndef BT_CONTACT_H_STRUCTS_INCLUDED
|
||||
#define BT_CONTACT_H_STRUCTS_INCLUDED
|
||||
|
||||
/*! \file gim_contact.h
|
||||
\author Francisco Leon Najera
|
||||
*/
|
||||
/*
|
||||
This source file is part of GIMPACT Library.
|
||||
|
||||
For the latest info, see http://gimpact.sourceforge.net/
|
||||
|
||||
Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371.
|
||||
email: projectileman@yahoo.com
|
||||
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "btTriangleShapeEx.h"
|
||||
|
||||
|
||||
/**
|
||||
Configuration var for applying interpolation of contact normals
|
||||
*/
|
||||
#define NORMAL_CONTACT_AVERAGE 1
|
||||
|
||||
#define CONTACT_DIFF_EPSILON 0.00001f
|
||||
|
||||
///The GIM_CONTACT is an internal GIMPACT structure, similar to btManifoldPoint.
|
||||
///@todo: remove and replace GIM_CONTACT by btManifoldPoint.
|
||||
class GIM_CONTACT
|
||||
{
|
||||
public:
|
||||
btVector3 m_point;
|
||||
btVector3 m_normal;
|
||||
btScalar m_depth;//Positive value indicates interpenetration
|
||||
btScalar m_distance;//Padding not for use
|
||||
int m_feature1;//Face number
|
||||
int m_feature2;//Face number
|
||||
public:
|
||||
GIM_CONTACT()
|
||||
{
|
||||
}
|
||||
|
||||
GIM_CONTACT(const GIM_CONTACT & contact):
|
||||
m_point(contact.m_point),
|
||||
m_normal(contact.m_normal),
|
||||
m_depth(contact.m_depth),
|
||||
m_feature1(contact.m_feature1),
|
||||
m_feature2(contact.m_feature2)
|
||||
{
|
||||
}
|
||||
|
||||
GIM_CONTACT(const btVector3 &point,const btVector3 & normal,
|
||||
btScalar depth, int feature1, int feature2):
|
||||
m_point(point),
|
||||
m_normal(normal),
|
||||
m_depth(depth),
|
||||
m_feature1(feature1),
|
||||
m_feature2(feature2)
|
||||
{
|
||||
}
|
||||
|
||||
//! Calcs key for coord classification
|
||||
SIMD_FORCE_INLINE unsigned int calc_key_contact() const
|
||||
{
|
||||
int _coords[] = {
|
||||
(int)(m_point[0]*1000.0f+1.0f),
|
||||
(int)(m_point[1]*1333.0f),
|
||||
(int)(m_point[2]*2133.0f+3.0f)};
|
||||
unsigned int _hash=0;
|
||||
unsigned int *_uitmp = (unsigned int *)(&_coords[0]);
|
||||
_hash = *_uitmp;
|
||||
_uitmp++;
|
||||
_hash += (*_uitmp)<<4;
|
||||
_uitmp++;
|
||||
_hash += (*_uitmp)<<8;
|
||||
return _hash;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void interpolate_normals( btVector3 * normals,int normal_count)
|
||||
{
|
||||
btVector3 vec_sum(m_normal);
|
||||
for(int i=0;i<normal_count;i++)
|
||||
{
|
||||
vec_sum += normals[i];
|
||||
}
|
||||
|
||||
btScalar vec_sum_len = vec_sum.length2();
|
||||
if(vec_sum_len <CONTACT_DIFF_EPSILON) return;
|
||||
|
||||
//GIM_INV_SQRT(vec_sum_len,vec_sum_len); // 1/sqrt(vec_sum_len)
|
||||
|
||||
m_normal = vec_sum/btSqrt(vec_sum_len);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // BT_CONTACT_H_STRUCTS_INCLUDED
|
@ -29,31 +29,7 @@ subject to the following restrictions:
|
||||
|
||||
#include "btBoxCollision.h"
|
||||
#include "btTriangleShapeEx.h"
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//! Overlapping pair
|
||||
struct GIM_PAIR
|
||||
{
|
||||
int m_index1;
|
||||
int m_index2;
|
||||
GIM_PAIR()
|
||||
{}
|
||||
|
||||
GIM_PAIR(const GIM_PAIR & p)
|
||||
{
|
||||
m_index1 = p.m_index1;
|
||||
m_index2 = p.m_index2;
|
||||
}
|
||||
|
||||
GIM_PAIR(int index1, int index2)
|
||||
{
|
||||
m_index1 = index1;
|
||||
m_index2 = index2;
|
||||
}
|
||||
};
|
||||
#include "btGImpactBvhStructs.h"
|
||||
|
||||
//! A pairset array
|
||||
class btPairSet: public btAlignedObjectArray<GIM_PAIR>
|
||||
@ -74,59 +50,6 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
///GIM_BVH_DATA is an internal GIMPACT collision structure to contain axis aligned bounding box
|
||||
struct GIM_BVH_DATA
|
||||
{
|
||||
btAABB m_bound;
|
||||
int m_data;
|
||||
};
|
||||
|
||||
//! Node Structure for trees
|
||||
class GIM_BVH_TREE_NODE
|
||||
{
|
||||
public:
|
||||
btAABB m_bound;
|
||||
protected:
|
||||
int m_escapeIndexOrDataIndex;
|
||||
public:
|
||||
GIM_BVH_TREE_NODE()
|
||||
{
|
||||
m_escapeIndexOrDataIndex = 0;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool isLeafNode() const
|
||||
{
|
||||
//skipindex is negative (internal node), triangleindex >=0 (leafnode)
|
||||
return (m_escapeIndexOrDataIndex>=0);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getEscapeIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex < 0);
|
||||
return -m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setEscapeIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = -index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getDataIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex >= 0);
|
||||
|
||||
return m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setDataIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = index;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
class GIM_BVH_DATA_ARRAY:public btAlignedObjectArray<GIM_BVH_DATA>
|
||||
{
|
||||
};
|
||||
@ -392,5 +315,4 @@ public:
|
||||
btPairSet & collision_pairs);
|
||||
};
|
||||
|
||||
|
||||
#endif // GIM_BOXPRUNING_H_INCLUDED
|
||||
|
105
src/BulletCollision/Gimpact/btGImpactBvhStructs.h
Normal file
105
src/BulletCollision/Gimpact/btGImpactBvhStructs.h
Normal file
@ -0,0 +1,105 @@
|
||||
#ifndef GIM_BOX_SET_STRUCT_H_INCLUDED
|
||||
#define GIM_BOX_SET_STRUCT_H_INCLUDED
|
||||
|
||||
/*! \file gim_box_set.h
|
||||
\author Francisco Leon Najera
|
||||
*/
|
||||
/*
|
||||
This source file is part of GIMPACT Library.
|
||||
|
||||
For the latest info, see http://gimpact.sourceforge.net/
|
||||
|
||||
Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371.
|
||||
email: projectileman@yahoo.com
|
||||
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
|
||||
#include "btBoxCollision.h"
|
||||
#include "btTriangleShapeEx.h"
|
||||
|
||||
//! Overlapping pair
|
||||
struct GIM_PAIR
|
||||
{
|
||||
int m_index1;
|
||||
int m_index2;
|
||||
GIM_PAIR()
|
||||
{}
|
||||
|
||||
GIM_PAIR(const GIM_PAIR & p)
|
||||
{
|
||||
m_index1 = p.m_index1;
|
||||
m_index2 = p.m_index2;
|
||||
}
|
||||
|
||||
GIM_PAIR(int index1, int index2)
|
||||
{
|
||||
m_index1 = index1;
|
||||
m_index2 = index2;
|
||||
}
|
||||
};
|
||||
|
||||
///GIM_BVH_DATA is an internal GIMPACT collision structure to contain axis aligned bounding box
|
||||
struct GIM_BVH_DATA
|
||||
{
|
||||
btAABB m_bound;
|
||||
int m_data;
|
||||
};
|
||||
|
||||
//! Node Structure for trees
|
||||
class GIM_BVH_TREE_NODE
|
||||
{
|
||||
public:
|
||||
btAABB m_bound;
|
||||
protected:
|
||||
int m_escapeIndexOrDataIndex;
|
||||
public:
|
||||
GIM_BVH_TREE_NODE()
|
||||
{
|
||||
m_escapeIndexOrDataIndex = 0;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool isLeafNode() const
|
||||
{
|
||||
//skipindex is negative (internal node), triangleindex >=0 (leafnode)
|
||||
return (m_escapeIndexOrDataIndex>=0);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getEscapeIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex < 0);
|
||||
return -m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setEscapeIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = -index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getDataIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex >= 0);
|
||||
|
||||
return m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setDataIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = index;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // GIM_BOXPRUNING_H_INCLUDED
|
@ -26,73 +26,7 @@ subject to the following restrictions:
|
||||
|
||||
#include "btGImpactBvh.h"
|
||||
#include "btQuantization.h"
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
///btQuantizedBvhNode is a compressed aabb node, 16 bytes.
|
||||
///Node can be used for leafnode or internal node. Leafnodes can point to 32-bit triangle index (non-negative range).
|
||||
ATTRIBUTE_ALIGNED16 (struct) BT_QUANTIZED_BVH_NODE
|
||||
{
|
||||
//12 bytes
|
||||
unsigned short int m_quantizedAabbMin[3];
|
||||
unsigned short int m_quantizedAabbMax[3];
|
||||
//4 bytes
|
||||
int m_escapeIndexOrDataIndex;
|
||||
|
||||
BT_QUANTIZED_BVH_NODE()
|
||||
{
|
||||
m_escapeIndexOrDataIndex = 0;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool isLeafNode() const
|
||||
{
|
||||
//skipindex is negative (internal node), triangleindex >=0 (leafnode)
|
||||
return (m_escapeIndexOrDataIndex>=0);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getEscapeIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex < 0);
|
||||
return -m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setEscapeIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = -index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getDataIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex >= 0);
|
||||
|
||||
return m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setDataIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool testQuantizedBoxOverlapp(
|
||||
unsigned short * quantizedMin,unsigned short * quantizedMax) const
|
||||
{
|
||||
if(m_quantizedAabbMin[0] > quantizedMax[0] ||
|
||||
m_quantizedAabbMax[0] < quantizedMin[0] ||
|
||||
m_quantizedAabbMin[1] > quantizedMax[1] ||
|
||||
m_quantizedAabbMax[1] < quantizedMin[1] ||
|
||||
m_quantizedAabbMin[2] > quantizedMax[2] ||
|
||||
m_quantizedAabbMax[2] < quantizedMin[2])
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#include "btGImpactQuantizedBvhStructs.h"
|
||||
|
||||
class GIM_QUANTIZED_BVH_NODE_ARRAY:public btAlignedObjectArray<BT_QUANTIZED_BVH_NODE>
|
||||
{
|
||||
@ -368,5 +302,4 @@ public:
|
||||
btPairSet & collision_pairs);
|
||||
};
|
||||
|
||||
|
||||
#endif // GIM_BOXPRUNING_H_INCLUDED
|
||||
|
91
src/BulletCollision/Gimpact/btGImpactQuantizedBvhStructs.h
Normal file
91
src/BulletCollision/Gimpact/btGImpactQuantizedBvhStructs.h
Normal file
@ -0,0 +1,91 @@
|
||||
#ifndef GIM_QUANTIZED_SET_STRUCTS_H_INCLUDED
|
||||
#define GIM_QUANTIZED_SET_STRUCTS_H_INCLUDED
|
||||
|
||||
/*! \file btGImpactQuantizedBvh.h
|
||||
\author Francisco Leon Najera
|
||||
*/
|
||||
/*
|
||||
This source file is part of GIMPACT Library.
|
||||
|
||||
For the latest info, see http://gimpact.sourceforge.net/
|
||||
|
||||
Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371.
|
||||
email: projectileman@yahoo.com
|
||||
|
||||
|
||||
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 "btGImpactBvh.h"
|
||||
#include "btQuantization.h"
|
||||
|
||||
///btQuantizedBvhNode is a compressed aabb node, 16 bytes.
|
||||
///Node can be used for leafnode or internal node. Leafnodes can point to 32-bit triangle index (non-negative range).
|
||||
ATTRIBUTE_ALIGNED16 (struct) BT_QUANTIZED_BVH_NODE
|
||||
{
|
||||
//12 bytes
|
||||
unsigned short int m_quantizedAabbMin[3];
|
||||
unsigned short int m_quantizedAabbMax[3];
|
||||
//4 bytes
|
||||
int m_escapeIndexOrDataIndex;
|
||||
|
||||
BT_QUANTIZED_BVH_NODE()
|
||||
{
|
||||
m_escapeIndexOrDataIndex = 0;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool isLeafNode() const
|
||||
{
|
||||
//skipindex is negative (internal node), triangleindex >=0 (leafnode)
|
||||
return (m_escapeIndexOrDataIndex>=0);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getEscapeIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex < 0);
|
||||
return -m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setEscapeIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = -index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE int getDataIndex() const
|
||||
{
|
||||
//btAssert(m_escapeIndexOrDataIndex >= 0);
|
||||
|
||||
return m_escapeIndexOrDataIndex;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setDataIndex(int index)
|
||||
{
|
||||
m_escapeIndexOrDataIndex = index;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool testQuantizedBoxOverlapp(
|
||||
unsigned short * quantizedMin,unsigned short * quantizedMax) const
|
||||
{
|
||||
if(m_quantizedAabbMin[0] > quantizedMax[0] ||
|
||||
m_quantizedAabbMax[0] < quantizedMin[0] ||
|
||||
m_quantizedAabbMin[1] > quantizedMax[1] ||
|
||||
m_quantizedAabbMax[1] < quantizedMin[1] ||
|
||||
m_quantizedAabbMin[2] > quantizedMax[2] ||
|
||||
m_quantizedAabbMax[2] < quantizedMin[2])
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif // GIM_QUANTIZED_SET_STRUCTS_H_INCLUDED
|
@ -228,7 +228,7 @@ public:
|
||||
inline void push_back_memcpy(const T & obj)
|
||||
{
|
||||
this->growingCheck();
|
||||
irr_simd_memcpy(&m_data[m_size],&obj,sizeof(T));
|
||||
gim_simd_memcpy(&m_data[m_size],&obj,sizeof(T));
|
||||
m_size++;
|
||||
}
|
||||
|
||||
|
@ -41,10 +41,13 @@ email: projectileman@yahoo.com
|
||||
|
||||
|
||||
|
||||
|
||||
#ifndef PLANEDIREPSILON
|
||||
#define PLANEDIREPSILON 0.0000001f
|
||||
#define PARALELENORMALS 0.000001f
|
||||
#endif
|
||||
|
||||
#ifndef PARALELENORMALS
|
||||
#define PARALELENORMALS 0.000001f
|
||||
#endif
|
||||
|
||||
#define TRIANGLE_NORMAL(v1,v2,v3,n)\
|
||||
{\
|
||||
|
@ -97,6 +97,8 @@ email: projectileman@yahoo.com
|
||||
// return test_cross_edge_box(edge,absolute_edge,pointa,pointb,extend,1,0,0,1);
|
||||
//}
|
||||
|
||||
#ifndef TEST_CROSS_EDGE_BOX_MCR
|
||||
|
||||
#define TEST_CROSS_EDGE_BOX_MCR(edge,absolute_edge,pointa,pointb,_extend,i_dir_0,i_dir_1,i_comp_0,i_comp_1)\
|
||||
{\
|
||||
const btScalar dir0 = -edge[i_dir_0];\
|
||||
@ -113,6 +115,7 @@ email: projectileman@yahoo.com
|
||||
if(pmin>rad || -rad>pmax) return false;\
|
||||
}\
|
||||
|
||||
#endif
|
||||
|
||||
#define TEST_CROSS_EDGE_BOX_X_AXIS_MCR(edge,absolute_edge,pointa,pointb,_extend)\
|
||||
{\
|
||||
@ -190,8 +193,9 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
#ifndef BOX_PLANE_EPSILON
|
||||
#define BOX_PLANE_EPSILON 0.000001f
|
||||
#endif
|
||||
|
||||
//! Axis aligned box
|
||||
class GIM_AABB
|
||||
@ -571,7 +575,7 @@ public:
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
#ifndef BT_BOX_COLLISION_H_INCLUDED
|
||||
//! Compairison of transformation objects
|
||||
SIMD_FORCE_INLINE bool btCompareTransformsEqual(const btTransform & t1,const btTransform & t2)
|
||||
{
|
||||
@ -582,6 +586,7 @@ SIMD_FORCE_INLINE bool btCompareTransformsEqual(const btTransform & t1,const btT
|
||||
if(!(t1.getBasis().getRow(2) == t2.getBasis().getRow(2)) ) return false;
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
@ -40,8 +40,15 @@ email: projectileman@yahoo.com
|
||||
/**
|
||||
Configuration var for applying interpolation of contact normals
|
||||
*/
|
||||
#ifndef NORMAL_CONTACT_AVERAGE
|
||||
#define NORMAL_CONTACT_AVERAGE 1
|
||||
#endif
|
||||
|
||||
#ifndef CONTACT_DIFF_EPSILON
|
||||
#define CONTACT_DIFF_EPSILON 0.00001f
|
||||
#endif
|
||||
|
||||
#ifndef BT_CONTACT_H_STRUCTS_INCLUDED
|
||||
|
||||
/// Structure for collision results
|
||||
///Functions for managing and sorting contacts resulting from a collision query.
|
||||
@ -121,6 +128,7 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
class gim_contact_array:public gim_array<GIM_CONTACT>
|
||||
{
|
||||
|
@ -38,8 +38,9 @@ email: projectileman@yahoo.com
|
||||
|
||||
|
||||
|
||||
|
||||
#ifndef MAX_TRI_CLIPPING
|
||||
#define MAX_TRI_CLIPPING 16
|
||||
#endif
|
||||
|
||||
//! Structure for collision
|
||||
struct GIM_TRIANGLE_CONTACT_DATA
|
||||
|
@ -67,10 +67,12 @@ struct btStorageResult : public btDiscreteCollisionDetectorInterface::Result
|
||||
btVector3 m_closestPointInB;
|
||||
btScalar m_distance; //negative means penetration !
|
||||
|
||||
protected:
|
||||
btStorageResult() : m_distance(btScalar(BT_LARGE_FLOAT))
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
public:
|
||||
virtual ~btStorageResult() {};
|
||||
|
||||
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
|
||||
|
@ -21,6 +21,8 @@ subject to the following restrictions:
|
||||
btScalar gContactBreakingThreshold = btScalar(0.02);
|
||||
ContactDestroyedCallback gContactDestroyedCallback = 0;
|
||||
ContactProcessedCallback gContactProcessedCallback = 0;
|
||||
ContactStartedCallback gContactStartedCallback = 0;
|
||||
ContactEndedCallback gContactEndedCallback = 0;
|
||||
///gContactCalcArea3Points will approximate the convex hull area using 3 points
|
||||
///when setting it to false, it will use 4 points to compute the area: it is more accurate but slower
|
||||
bool gContactCalcArea3Points = true;
|
||||
|
@ -28,10 +28,18 @@ struct btCollisionResult;
|
||||
///maximum contact breaking and merging threshold
|
||||
extern btScalar gContactBreakingThreshold;
|
||||
|
||||
#ifndef SWIG
|
||||
class btPersistentManifold;
|
||||
|
||||
typedef bool (*ContactDestroyedCallback)(void* userPersistentData);
|
||||
typedef bool (*ContactProcessedCallback)(btManifoldPoint& cp,void* body0,void* body1);
|
||||
typedef void (*ContactStartedCallback)(btPersistentManifold* const &manifold);
|
||||
typedef void (*ContactEndedCallback)(btPersistentManifold* const &manifold);
|
||||
extern ContactDestroyedCallback gContactDestroyedCallback;
|
||||
extern ContactProcessedCallback gContactProcessedCallback;
|
||||
extern ContactStartedCallback gContactStartedCallback;
|
||||
extern ContactEndedCallback gContactEndedCallback;
|
||||
#endif //SWIG
|
||||
|
||||
//the enum starts at 1024 to avoid type conflicts with btTypedConstraint
|
||||
enum btContactManifoldTypes
|
||||
@ -171,6 +179,11 @@ public:
|
||||
|
||||
btAssert(m_pointCache[lastUsedIndex].m_userPersistentData==0);
|
||||
m_cachedPoints--;
|
||||
|
||||
if (gContactEndedCallback && m_cachedPoints == 0)
|
||||
{
|
||||
gContactEndedCallback(this);
|
||||
}
|
||||
}
|
||||
void replaceContactPoint(const btManifoldPoint& newPoint, int insertIndex)
|
||||
{
|
||||
@ -235,6 +248,11 @@ public:
|
||||
{
|
||||
clearUserCache(m_pointCache[i]);
|
||||
}
|
||||
|
||||
if (gContactEndedCallback && m_cachedPoints)
|
||||
{
|
||||
gContactEndedCallback(this);
|
||||
}
|
||||
m_cachedPoints = 0;
|
||||
}
|
||||
|
||||
|
@ -28,11 +28,13 @@ protected:
|
||||
|
||||
btPersistentManifold m_contactManifold;
|
||||
|
||||
public:
|
||||
protected:
|
||||
|
||||
|
||||
btContactConstraint(btPersistentManifold* contactManifold,btRigidBody& rbA,btRigidBody& rbB);
|
||||
|
||||
public:
|
||||
|
||||
void setContactManifold(btPersistentManifold* contactManifold);
|
||||
|
||||
btPersistentManifold* getContactManifold()
|
||||
|
@ -19,7 +19,7 @@ class btDynamicsWorld;
|
||||
#include "btWheelInfo.h"
|
||||
#include "BulletDynamics/Dynamics/btActionInterface.h"
|
||||
|
||||
class btVehicleTuning;
|
||||
//class btVehicleTuning;
|
||||
|
||||
///rayCast vehicle, very special constraint that turn a rigidbody into a vehicle.
|
||||
class btRaycastVehicle : public btActionInterface
|
||||
|
@ -79,6 +79,8 @@ struct btWheelInfo
|
||||
|
||||
void* m_clientInfo;//can be used to store pointer to sync transforms...
|
||||
|
||||
btWheelInfo() {}
|
||||
|
||||
btWheelInfo(btWheelInfoConstructionInfo& ci)
|
||||
|
||||
{
|
||||
|
@ -68,6 +68,10 @@ typedef btScalar idScalar;
|
||||
#ifdef BT_USE_DOUBLE_PRECISION
|
||||
#define BT_ID_USE_DOUBLE_PRECISION
|
||||
#endif
|
||||
|
||||
#ifndef BT_USE_INVERSE_DYNAMICS_WITH_BULLET2
|
||||
|
||||
|
||||
// use bullet types for arrays and array indices
|
||||
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||
// this is to make it work with C++2003, otherwise we could do this:
|
||||
@ -78,7 +82,20 @@ struct idArray {
|
||||
typedef b3AlignedObjectArray<T> type;
|
||||
};
|
||||
typedef int idArrayIdx;
|
||||
#define ID_DECLARE_ALIGNED_ALLOCATOR B3_DECLARE_ALIGNED_ALLOCATOR
|
||||
#define ID_DECLARE_ALIGNED_ALLOCATOR() B3_DECLARE_ALIGNED_ALLOCATOR()
|
||||
|
||||
#else // BT_USE_INVERSE_DYNAMICS_WITH_BULLET2
|
||||
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
template <typename T>
|
||||
struct idArray {
|
||||
typedef btAlignedObjectArray<T> type;
|
||||
};
|
||||
typedef int idArrayIdx;
|
||||
#define ID_DECLARE_ALIGNED_ALLOCATOR() BT_DECLARE_ALIGNED_ALLOCATOR()
|
||||
|
||||
#endif // BT_USE_INVERSE_DYNAMICS_WITH_BULLET2
|
||||
|
||||
|
||||
// use bullet's allocator functions
|
||||
#define idMalloc btAllocFunc
|
||||
|
@ -5,7 +5,7 @@
|
||||
/// name of file being compiled, without leading path components
|
||||
#define __INVDYN_FILE_WO_DIR__ (strrchr(__FILE__, '/') ? strrchr(__FILE__, '/') + 1 : __FILE__)
|
||||
|
||||
#ifndef BT_ID_WO_BULLET
|
||||
#if !defined(BT_ID_WO_BULLET) && !defined(BT_USE_INVERSE_DYNAMICS_WITH_BULLET2)
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
#define error_message(...) b3Error(__VA_ARGS__)
|
||||
#define warning_message(...) b3Warning(__VA_ARGS__)
|
||||
@ -19,11 +19,6 @@
|
||||
fprintf(stderr, __VA_ARGS__); \
|
||||
} while (0)
|
||||
/// print warning message with file/line information
|
||||
#define warning_message(...) \
|
||||
do { \
|
||||
fprintf(stderr, "[Warning:%s:%d] ", __INVDYN_FILE_WO_DIR__, __LINE__); \
|
||||
fprintf(stderr, __VA_ARGS__); \
|
||||
} while (0)
|
||||
#define warning_message(...) \
|
||||
do { \
|
||||
fprintf(stderr, "[Warning:%s:%d] ", __INVDYN_FILE_WO_DIR__, __LINE__); \
|
||||
|
@ -617,7 +617,7 @@ public:
|
||||
RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
|
||||
void Process(const btDbvtNode* leaf);
|
||||
|
||||
static inline btScalar rayFromToTriangle(const btVector3& rayFrom,
|
||||
static /*inline*/ btScalar rayFromToTriangle(const btVector3& rayFrom,
|
||||
const btVector3& rayTo,
|
||||
const btVector3& rayNormalizedDirection,
|
||||
const btVector3& a,
|
||||
|
@ -20,7 +20,9 @@ subject to the following restrictions:
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletSoftBody/btSoftBody.h"
|
||||
|
||||
#ifndef BT_SOFT_RIGID_DYNAMICS_WORLD_H
|
||||
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
|
||||
#endif
|
||||
|
||||
class btSoftBodySolver;
|
||||
|
||||
|
@ -65,9 +65,11 @@ btLeaveProfileZoneFunc* btGetCurrentLeaveProfileZoneFunc();
|
||||
void btSetCustomEnterProfileZoneFunc(btEnterProfileZoneFunc* enterFunc);
|
||||
void btSetCustomLeaveProfileZoneFunc(btLeaveProfileZoneFunc* leaveFunc);
|
||||
|
||||
|
||||
#ifndef BT_NO_PROFILE // FIX redefinition
|
||||
//To disable built-in profiling, please comment out next line
|
||||
//#define BT_NO_PROFILE 1
|
||||
#endif //BT_NO_PROFILE
|
||||
|
||||
#ifndef BT_NO_PROFILE
|
||||
//btQuickprofGetCurrentThreadIndex will return -1 if thread index cannot be determined,
|
||||
//otherwise returns thread index in range [0..maxThreads]
|
||||
|
@ -32,6 +32,28 @@ inline int btGetVersion()
|
||||
return BT_BULLET_VERSION;
|
||||
}
|
||||
|
||||
|
||||
// The following macro "BT_NOT_EMPTY_FILE" can be put into a file
|
||||
// in order suppress the MS Visual C++ Linker warning 4221
|
||||
//
|
||||
// warning LNK4221: no public symbols found; archive member will be inaccessible
|
||||
//
|
||||
// This warning occurs on PC and XBOX when a file compiles out completely
|
||||
// has no externally visible symbols which may be dependant on configuration
|
||||
// #defines and options.
|
||||
//
|
||||
// see more https://stackoverflow.com/questions/1822887/what-is-the-best-way-to-eliminate-ms-visual-c-linker-warning-warning-lnk422
|
||||
|
||||
#if defined (_MSC_VER)
|
||||
#define BT_NOT_EMPTY_FILE_CAT_II(p, res) res
|
||||
#define BT_NOT_EMPTY_FILE_CAT_I(a, b) BT_NOT_EMPTY_FILE_CAT_II(~, a ## b)
|
||||
#define BT_NOT_EMPTY_FILE_CAT(a, b) BT_NOT_EMPTY_FILE_CAT_I(a, b)
|
||||
#define BT_NOT_EMPTY_FILE namespace { char BT_NOT_EMPTY_FILE_CAT(NoEmptyFileDummy, __COUNTER__); }
|
||||
#else
|
||||
#define BT_NOT_EMPTY_FILE
|
||||
#endif
|
||||
|
||||
|
||||
// clang and most formatting tools don't support indentation of preprocessor guards, so turn it off
|
||||
// clang-format off
|
||||
#if defined(DEBUG) || defined (_DEBUG)
|
||||
|
Loading…
Reference in New Issue
Block a user