Merge pull request #1348 from erwincoumans/master
remote b3GjkPairDetector, Update pybullet autogenerated C# bindings (for Unity 3D), update pybullet_quickstartguide.pdf
This commit is contained in:
@@ -70,7 +70,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_0.stl"/>
|
<mesh filename="meshes/link_0.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Grey"/>
|
<material name="Grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -99,7 +99,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_1.stl"/>
|
<mesh filename="meshes/link_1.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Blue"/>
|
<material name="Blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -128,7 +128,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_2.stl"/>
|
<mesh filename="meshes/link_2.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Blue"/>
|
<material name="Blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -157,7 +157,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_3.stl"/>
|
<mesh filename="meshes/link_3.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Orange"/>
|
<material name="Orange"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -186,7 +186,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_4.stl"/>
|
<mesh filename="meshes/link_4.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Blue"/>
|
<material name="Blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -215,7 +215,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_5.stl"/>
|
<mesh filename="meshes/link_5.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Blue"/>
|
<material name="Blue"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -244,7 +244,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_6.stl"/>
|
<mesh filename="meshes/link_6.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Orange"/>
|
<material name="Orange"/>
|
||||||
</visual>
|
</visual>
|
||||||
@@ -273,7 +273,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="meshes/link_7.stl"/>
|
<mesh filename="meshes/link_7.obj"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="Grey"/>
|
<material name="Grey"/>
|
||||||
</visual>
|
</visual>
|
||||||
|
|||||||
Binary file not shown.
@@ -622,22 +622,22 @@ void GLInstancingRenderer::writeTransforms()
|
|||||||
{
|
{
|
||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("b3Assert(glGetError() 1");
|
//B3_PROFILE("b3Assert(glGetError() 1");
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBindBuffer");
|
//B3_PROFILE("glBindBuffer");
|
||||||
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
|
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("glFlush()");
|
//B3_PROFILE("glFlush()");
|
||||||
//without the flush, the glBufferSubData can spike to really slow (seconds slow)
|
//without the flush, the glBufferSubData can spike to really slow (seconds slow)
|
||||||
glFlush();
|
glFlush();
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("b3Assert(glGetError() 2");
|
//B3_PROFILE("b3Assert(glGetError() 2");
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -666,22 +666,22 @@ void GLInstancingRenderer::writeTransforms()
|
|||||||
{
|
{
|
||||||
// printf("m_data->m_totalNumInstances = %d\n", m_data->m_totalNumInstances);
|
// printf("m_data->m_totalNumInstances = %d\n", m_data->m_totalNumInstances);
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBufferSubData pos");
|
//B3_PROFILE("glBufferSubData pos");
|
||||||
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4,
|
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4,
|
||||||
&m_data->m_instance_positions_ptr[0]);
|
&m_data->m_instance_positions_ptr[0]);
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBufferSubData orn");
|
// B3_PROFILE("glBufferSubData orn");
|
||||||
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4,
|
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4,
|
||||||
&m_data->m_instance_quaternion_ptr[0]);
|
&m_data->m_instance_quaternion_ptr[0]);
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBufferSubData color");
|
// B3_PROFILE("glBufferSubData color");
|
||||||
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4,
|
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4,
|
||||||
&m_data->m_instance_colors_ptr[0]);
|
&m_data->m_instance_colors_ptr[0]);
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBufferSubData scale");
|
// B3_PROFILE("glBufferSubData scale");
|
||||||
glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3,
|
glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3,
|
||||||
&m_data->m_instance_scale_ptr[0]);
|
&m_data->m_instance_scale_ptr[0]);
|
||||||
}
|
}
|
||||||
@@ -756,12 +756,12 @@ void GLInstancingRenderer::writeTransforms()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("glBindBuffer 2");
|
// B3_PROFILE("glBindBuffer 2");
|
||||||
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
|
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("b3Assert(glGetError() 4");
|
// B3_PROFILE("b3Assert(glGetError() 4");
|
||||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -10,25 +10,8 @@ using System;
|
|||||||
|
|
||||||
public class NewBehaviourScript : MonoBehaviour {
|
public class NewBehaviourScript : MonoBehaviour {
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3ConnectSharedMemory")]
|
|
||||||
public static extern System.IntPtr b3ConnectSharedMemory(int key);
|
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3CreateInProcessPhysicsServerAndConnect")]
|
|
||||||
public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv);
|
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitStepSimulationCommand")]
|
|
||||||
public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient);
|
|
||||||
|
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3LoadUrdfCommandInit")]
|
|
||||||
public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName);
|
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitResetSimulationCommand")]
|
|
||||||
public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient);
|
|
||||||
|
|
||||||
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3SubmitClientCommandAndWaitStatus")]
|
|
||||||
public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle);
|
|
||||||
|
|
||||||
|
|
||||||
[DllImport("TestCppPlug.dll")]
|
[DllImport("TestCppPlug.dll")]
|
||||||
static extern int Add(int a, int b);
|
static extern int Add(int a, int b);
|
||||||
@@ -60,27 +43,45 @@ public class NewBehaviourScript : MonoBehaviour {
|
|||||||
CallMe(IWasCalled);
|
CallMe(IWasCalled);
|
||||||
sharedAPI = CreateSharedAPI(30);
|
sharedAPI = CreateSharedAPI(30);
|
||||||
|
|
||||||
IntPtr pybullet = b3ConnectSharedMemory(12347);
|
pybullet = NativeMethods.b3ConnectPhysicsDirect();// SharedMemory(12347);
|
||||||
IntPtr cmd = b3InitResetSimulationCommand(pybullet);
|
IntPtr cmd = NativeMethods.b3InitResetSimulationCommand(pybullet);
|
||||||
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||||
cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf");
|
int numBodies = NativeMethods.b3GetNumBodies(pybullet);
|
||||||
status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf");
|
||||||
|
status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||||
|
EnumSharedMemoryServerStatus statusType = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status);
|
||||||
|
if (statusType == EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED)
|
||||||
|
{
|
||||||
|
numBodies = NativeMethods.b3GetNumBodies(pybullet);
|
||||||
|
text.text = numBodies.ToString();
|
||||||
|
if (numBodies > 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
//b3BodyInfo info=new b3BodyInfo();
|
||||||
|
//NativeMethods.b3GetBodyInfo(pybullet, 0, ref info );
|
||||||
|
//text.text = info.m_baseName;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
//IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr);
|
//IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update is called once per frame
|
|
||||||
void Update () {
|
|
||||||
IntPtr cmd = b3InitStepSimulationCommand(pybullet);
|
|
||||||
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
|
||||||
|
|
||||||
//System.IO.Directory.GetCurrentDirectory().ToString();//
|
// Update is called once per frame
|
||||||
//text.text = Add(4, 5).ToString();
|
void Update () {
|
||||||
text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString();
|
//if (pybullet != IntPtr.Zero)
|
||||||
|
{
|
||||||
|
IntPtr cmd = NativeMethods.b3InitStepSimulationCommand(pybullet);
|
||||||
|
IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||||
|
|
||||||
|
//text.text = System.IO.Directory.GetCurrentDirectory().ToString();
|
||||||
|
//text.text = Add(4, 5).ToString();
|
||||||
|
//text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void OnDestroy()
|
void OnDestroy()
|
||||||
{
|
{
|
||||||
|
NativeMethods.b3DisconnectSharedMemory(pybullet);
|
||||||
DeleteSharedAPI(sharedAPI);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
2
setup.py
2
setup.py
@@ -441,7 +441,7 @@ print("-----")
|
|||||||
|
|
||||||
setup(
|
setup(
|
||||||
name = 'pybullet',
|
name = 'pybullet',
|
||||||
version='1.4.9',
|
version='1.5.1',
|
||||||
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||||
url='https://github.com/bulletphysics/bullet3',
|
url='https://github.com/bulletphysics/bullet3',
|
||||||
|
|||||||
@@ -12,7 +12,6 @@ SET(Bullet3OpenCL_clew_SRCS
|
|||||||
NarrowphaseCollision/b3ContactCache.cpp
|
NarrowphaseCollision/b3ContactCache.cpp
|
||||||
NarrowphaseCollision/b3ConvexHullContact.cpp
|
NarrowphaseCollision/b3ConvexHullContact.cpp
|
||||||
NarrowphaseCollision/b3GjkEpa.cpp
|
NarrowphaseCollision/b3GjkEpa.cpp
|
||||||
NarrowphaseCollision/b3GjkPairDetector.cpp
|
|
||||||
NarrowphaseCollision/b3OptimizedBvh.cpp
|
NarrowphaseCollision/b3OptimizedBvh.cpp
|
||||||
NarrowphaseCollision/b3QuantizedBvh.cpp
|
NarrowphaseCollision/b3QuantizedBvh.cpp
|
||||||
NarrowphaseCollision/b3StridingMeshInterface.cpp
|
NarrowphaseCollision/b3StridingMeshInterface.cpp
|
||||||
|
|||||||
@@ -24,8 +24,8 @@ bool clipConvexFacesAndFindContactsCPU = false;//false;//true;
|
|||||||
bool reduceConcaveContactsOnGPU = true;//false;
|
bool reduceConcaveContactsOnGPU = true;//false;
|
||||||
bool reduceConvexContactsOnGPU = true;//false;
|
bool reduceConvexContactsOnGPU = true;//false;
|
||||||
bool findConvexClippingFacesGPU = true;
|
bool findConvexClippingFacesGPU = true;
|
||||||
bool useGjk = true;///option for CPU/host testing, when findSeparatingAxisOnGpu = false
|
bool useGjk = false;///option for CPU/host testing, when findSeparatingAxisOnGpu = false
|
||||||
bool useGjkContacts = true;//////option for CPU/host testing when findSeparatingAxisOnGpu = false
|
bool useGjkContacts = false;//////option for CPU/host testing when findSeparatingAxisOnGpu = false
|
||||||
|
|
||||||
|
|
||||||
static int myframecount=0;///for testing
|
static int myframecount=0;///for testing
|
||||||
@@ -2606,146 +2606,6 @@ void computeContactSphereConvex(int pairIndex,
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
#include "b3GjkPairDetector.h"
|
|
||||||
#include "b3GjkEpa.h"
|
|
||||||
#include "b3VoronoiSimplexSolver.h"
|
|
||||||
|
|
||||||
int computeContactConvexConvex( b3AlignedObjectArray<b3Int4>& pairs,
|
|
||||||
int pairIndex,
|
|
||||||
int bodyIndexA, int bodyIndexB,
|
|
||||||
int collidableIndexA, int collidableIndexB,
|
|
||||||
const b3AlignedObjectArray<b3RigidBodyData>& rigidBodies,
|
|
||||||
const b3AlignedObjectArray<b3Collidable>& collidables,
|
|
||||||
const b3AlignedObjectArray<b3ConvexPolyhedronData>& convexShapes,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& convexVertices,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& uniqueEdges,
|
|
||||||
const b3AlignedObjectArray<int>& convexIndices,
|
|
||||||
const b3AlignedObjectArray<b3GpuFace>& faces,
|
|
||||||
b3AlignedObjectArray<b3Contact4>& globalContactsOut,
|
|
||||||
int& nGlobalContactsOut,
|
|
||||||
int maxContactCapacity,
|
|
||||||
b3AlignedObjectArray<int>&hostHasSepAxis,
|
|
||||||
b3AlignedObjectArray<b3Vector3>&hostSepAxis
|
|
||||||
|
|
||||||
|
|
||||||
//,const b3AlignedObjectArray<b3Contact4>& oldContacts
|
|
||||||
)
|
|
||||||
{
|
|
||||||
int contactIndex = -1;
|
|
||||||
b3VoronoiSimplexSolver simplexSolver;
|
|
||||||
b3GjkEpaSolver2 epaSolver;
|
|
||||||
|
|
||||||
b3GjkPairDetector gjkDetector(&simplexSolver,&epaSolver);
|
|
||||||
|
|
||||||
b3Transform transA;
|
|
||||||
transA.setOrigin(rigidBodies[bodyIndexA].m_pos);
|
|
||||||
transA.setRotation(rigidBodies[bodyIndexA].m_quat);
|
|
||||||
|
|
||||||
b3Transform transB;
|
|
||||||
transB.setOrigin(rigidBodies[bodyIndexB].m_pos);
|
|
||||||
transB.setRotation(rigidBodies[bodyIndexB].m_quat);
|
|
||||||
float maximumDistanceSquared = 1e30f;
|
|
||||||
|
|
||||||
b3Vector3 resultPointOnBWorld;
|
|
||||||
b3Vector3 sepAxis2=b3MakeVector3(0,1,0);
|
|
||||||
b3Scalar distance2 = 1e30f;
|
|
||||||
|
|
||||||
int shapeIndexA = collidables[collidableIndexA].m_shapeIndex;
|
|
||||||
int shapeIndexB = collidables[collidableIndexB].m_shapeIndex;
|
|
||||||
|
|
||||||
//int sz = sizeof(b3Contact4);
|
|
||||||
|
|
||||||
bool result2 = getClosestPoints(&gjkDetector, transA, transB,
|
|
||||||
convexShapes[shapeIndexA], convexShapes[shapeIndexB],
|
|
||||||
convexVertices,convexVertices,
|
|
||||||
maximumDistanceSquared,
|
|
||||||
sepAxis2,
|
|
||||||
distance2,
|
|
||||||
resultPointOnBWorld);
|
|
||||||
|
|
||||||
|
|
||||||
if (result2)
|
|
||||||
{
|
|
||||||
if (nGlobalContactsOut<maxContactCapacity)
|
|
||||||
{
|
|
||||||
contactIndex = nGlobalContactsOut;
|
|
||||||
globalContactsOut.expand();
|
|
||||||
b3Contact4& newContact = globalContactsOut.at(nGlobalContactsOut);
|
|
||||||
newContact.m_batchIdx = 0;//i;
|
|
||||||
newContact.m_bodyAPtrAndSignBit = (rigidBodies.at(bodyIndexA).m_invMass==0)? -bodyIndexA:bodyIndexA;
|
|
||||||
newContact.m_bodyBPtrAndSignBit = (rigidBodies.at(bodyIndexB).m_invMass==0)? -bodyIndexB:bodyIndexB;
|
|
||||||
|
|
||||||
newContact.m_frictionCoeffCmp = 45874;
|
|
||||||
newContact.m_restituitionCoeffCmp = 0;
|
|
||||||
|
|
||||||
|
|
||||||
int numPoints = 0;
|
|
||||||
if (pairs[pairIndex].z>=0)
|
|
||||||
{
|
|
||||||
//printf("add existing points?\n");
|
|
||||||
//refresh
|
|
||||||
|
|
||||||
int numOldPoints = 0;//oldContacts[pairs[pairIndex].z].getNPoints();
|
|
||||||
if (numOldPoints)
|
|
||||||
{
|
|
||||||
//newContact = oldContacts[pairs[pairIndex].z];
|
|
||||||
#ifdef PERSISTENT_CONTACTS_HOST
|
|
||||||
b3ContactCache::refreshContactPoints(transA,transB,newContact);
|
|
||||||
#endif //PERSISTENT_CONTACTS_HOST
|
|
||||||
}
|
|
||||||
numPoints = b3Contact4Data_getNumPoints(&newContact);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
int insertIndex = m_manifoldPtr->getCacheEntry(newPt);
|
|
||||||
if (insertIndex >= 0)
|
|
||||||
{
|
|
||||||
//const btManifoldPoint& oldPoint = m_manifoldPtr->getContactPoint(insertIndex);
|
|
||||||
m_manifoldPtr->replaceContactPoint(newPt,insertIndex);
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
insertIndex = m_manifoldPtr->addManifoldPoint(newPt);
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
|
|
||||||
int p=numPoints;
|
|
||||||
if (numPoints<4)
|
|
||||||
{
|
|
||||||
numPoints++;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
p=3;
|
|
||||||
}
|
|
||||||
|
|
||||||
{
|
|
||||||
resultPointOnBWorld.w = distance2;
|
|
||||||
newContact.m_worldPosB[p] = resultPointOnBWorld;
|
|
||||||
#ifdef PERSISTENT_CONTACTS_HOST
|
|
||||||
b3Vector3 resultPointOnAWorld = resultPointOnBWorld+distance2*sepAxis2;
|
|
||||||
newContact.m_localPosA[p] = transA.inverse()*resultPointOnAWorld;
|
|
||||||
newContact.m_localPosB[p] = transB.inverse()*resultPointOnBWorld;
|
|
||||||
#endif
|
|
||||||
newContact.m_worldNormalOnB = sepAxis2;
|
|
||||||
|
|
||||||
|
|
||||||
hostHasSepAxis[pairIndex] = 1;
|
|
||||||
hostSepAxis[pairIndex] =sepAxis2;
|
|
||||||
//printf("sepAxis[%d]=%f,%f,%f,%f\n",pairIndex,sepAxis2.x,sepAxis2.y,sepAxis2.z,sepAxis2.w);
|
|
||||||
}
|
|
||||||
//printf("bodyIndexA %d,bodyIndexB %d,normal=%f,%f,%f numPoints %d\n",bodyIndexA,bodyIndexB,normalOnSurfaceB.x,normalOnSurfaceB.y,normalOnSurfaceB.z,numPoints);
|
|
||||||
newContact.m_worldNormalOnB.w = (b3Scalar)numPoints;
|
|
||||||
|
|
||||||
|
|
||||||
nGlobalContactsOut++;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
b3Error("Error: exceeding contact capacity (%d/%d)\n", nGlobalContactsOut,maxContactCapacity);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return contactIndex;
|
|
||||||
}
|
|
||||||
|
|
||||||
int computeContactConvexConvex2(
|
int computeContactConvexConvex2(
|
||||||
int pairIndex,
|
int pairIndex,
|
||||||
@@ -3025,8 +2885,8 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
|||||||
hostCollidables[collidableIndexB].m_shapeType == SHAPE_CONVEX_HULL)
|
hostCollidables[collidableIndexB].m_shapeType == SHAPE_CONVEX_HULL)
|
||||||
{
|
{
|
||||||
//printf("hostPairs[i].z=%d\n",hostPairs[i].z);
|
//printf("hostPairs[i].z=%d\n",hostPairs[i].z);
|
||||||
//int contactIndex = computeContactConvexConvex2(i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
int contactIndex = computeContactConvexConvex2( i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
||||||
int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
//int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
||||||
|
|
||||||
|
|
||||||
if (contactIndex>=0)
|
if (contactIndex>=0)
|
||||||
@@ -3538,9 +3398,10 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//int contactIndex = computeContactConvexConvex2( i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf, hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
||||||
|
b3AlignedObjectArray<b3Contact4> oldHostContacts;
|
||||||
int result;
|
int result;
|
||||||
result = computeContactConvexConvex( hostPairs,
|
result = computeContactConvexConvex2( //hostPairs,
|
||||||
pairIndex,
|
pairIndex,
|
||||||
bodyIndexA, bodyIndexB,
|
bodyIndexA, bodyIndexB,
|
||||||
collidableIndexA, collidableIndexB,
|
collidableIndexA, collidableIndexB,
|
||||||
@@ -3554,8 +3415,9 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
|||||||
hostContacts,
|
hostContacts,
|
||||||
nGlobalContactsOut,
|
nGlobalContactsOut,
|
||||||
maxContactCapacity,
|
maxContactCapacity,
|
||||||
hostHasSepAxis,
|
oldHostContacts
|
||||||
hostSepAxis
|
//hostHasSepAxis,
|
||||||
|
//hostSepAxis
|
||||||
|
|
||||||
);
|
);
|
||||||
}//mpr
|
}//mpr
|
||||||
|
|||||||
@@ -1,533 +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 "b3GjkPairDetector.h"
|
|
||||||
#include "Bullet3Common/b3Transform.h"
|
|
||||||
#include "b3VoronoiSimplexSolver.h"
|
|
||||||
#include "Bullet3Collision/NarrowPhaseCollision/shared/b3ConvexPolyhedronData.h"
|
|
||||||
#include "b3VectorFloat4.h"
|
|
||||||
#include "b3GjkEpa.h"
|
|
||||||
#include "b3SupportMappings.h"
|
|
||||||
|
|
||||||
//must be above the machine epsilon
|
|
||||||
#define REL_ERROR2 b3Scalar(1.0e-6)
|
|
||||||
|
|
||||||
//temp globals, to improve GJK/EPA/penetration calculations
|
|
||||||
int gNumDeepPenetrationChecks2 = 0;
|
|
||||||
int gNumGjkChecks2 = 0;
|
|
||||||
int gGjkSeparatingAxis2=0;
|
|
||||||
int gEpaSeparatingAxis2=0;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
b3GjkPairDetector::b3GjkPairDetector(b3VoronoiSimplexSolver* simplexSolver,b3GjkEpaSolver2* penetrationDepthSolver)
|
|
||||||
:m_cachedSeparatingAxis(b3MakeVector3(b3Scalar(0.),b3Scalar(-1.),b3Scalar(0.))),
|
|
||||||
m_penetrationDepthSolver(penetrationDepthSolver),
|
|
||||||
m_simplexSolver(simplexSolver),
|
|
||||||
m_ignoreMargin(false),
|
|
||||||
m_lastUsedMethod(-1),
|
|
||||||
m_catchDegeneracies(1),
|
|
||||||
m_fixContactNormalDirection(1)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
bool calcPenDepth( b3VoronoiSimplexSolver& simplexSolver,
|
|
||||||
const b3Transform& transformA, const b3Transform& transformB,
|
|
||||||
const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesA,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesB,
|
|
||||||
b3Vector3& v, b3Vector3& wWitnessOnA, b3Vector3& wWitnessOnB)
|
|
||||||
{
|
|
||||||
|
|
||||||
(void)v;
|
|
||||||
(void)simplexSolver;
|
|
||||||
|
|
||||||
b3Vector3 guessVector(transformB.getOrigin()-transformA.getOrigin());
|
|
||||||
b3GjkEpaSolver2::sResults results;
|
|
||||||
|
|
||||||
|
|
||||||
if(b3GjkEpaSolver2::Penetration(transformA,transformB,&hullA,&hullB,verticesA,verticesB,guessVector,results))
|
|
||||||
{
|
|
||||||
wWitnessOnA = results.witnesses[0];
|
|
||||||
wWitnessOnB = results.witnesses[1];
|
|
||||||
v = results.normal;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
if(b3GjkEpaSolver2::Distance(transformA,transformB,&hullA,&hullB,verticesA,verticesB,guessVector,results))
|
|
||||||
{
|
|
||||||
wWitnessOnA = results.witnesses[0];
|
|
||||||
wWitnessOnB = results.witnesses[1];
|
|
||||||
v = results.normal;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
#define dot3F4 b3Dot
|
|
||||||
|
|
||||||
inline void project(const b3ConvexPolyhedronData& hull, const float4& pos, const b3Quaternion& orn, const float4& dir, const b3AlignedObjectArray<b3Vector3>& vertices, b3Scalar& min, b3Scalar& max)
|
|
||||||
{
|
|
||||||
min = FLT_MAX;
|
|
||||||
max = -FLT_MAX;
|
|
||||||
int numVerts = hull.m_numVertices;
|
|
||||||
|
|
||||||
const float4 localDir = b3QuatRotate(orn.inverse(),dir);
|
|
||||||
|
|
||||||
b3Scalar offset = dot3F4(pos,dir);
|
|
||||||
|
|
||||||
for(int i=0;i<numVerts;i++)
|
|
||||||
{
|
|
||||||
//b3Vector3 pt = trans * vertices[m_vertexOffset+i];
|
|
||||||
//b3Scalar dp = pt.dot(dir);
|
|
||||||
//b3Vector3 vertex = vertices[hull.m_vertexOffset+i];
|
|
||||||
b3Scalar dp = dot3F4((float4&)vertices[hull.m_vertexOffset+i],localDir);
|
|
||||||
//b3Assert(dp==dpL);
|
|
||||||
if(dp < min) min = dp;
|
|
||||||
if(dp > max) max = dp;
|
|
||||||
}
|
|
||||||
if(min>max)
|
|
||||||
{
|
|
||||||
b3Scalar tmp = min;
|
|
||||||
min = max;
|
|
||||||
max = tmp;
|
|
||||||
}
|
|
||||||
min += offset;
|
|
||||||
max += offset;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
static bool TestSepAxis(const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB,
|
|
||||||
const float4& posA,const b3Quaternion& ornA,
|
|
||||||
const float4& posB,const b3Quaternion& ornB,
|
|
||||||
float4& sep_axis, const b3AlignedObjectArray<b3Vector3>& verticesA,const b3AlignedObjectArray<b3Vector3>& verticesB,b3Scalar& depth)
|
|
||||||
{
|
|
||||||
b3Scalar Min0,Max0;
|
|
||||||
b3Scalar Min1,Max1;
|
|
||||||
project(hullA,posA,ornA,sep_axis,verticesA, Min0, Max0);
|
|
||||||
project(hullB,posB,ornB, sep_axis,verticesB, Min1, Max1);
|
|
||||||
|
|
||||||
if(Max0<Min1 || Max1<Min0)
|
|
||||||
return false;
|
|
||||||
|
|
||||||
b3Scalar d0 = Max0 - Min1;
|
|
||||||
b3Assert(d0>=0.0f);
|
|
||||||
b3Scalar d1 = Max1 - Min0;
|
|
||||||
b3Assert(d1>=0.0f);
|
|
||||||
if (d0<d1)
|
|
||||||
{
|
|
||||||
depth = d0;
|
|
||||||
sep_axis *=-1;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
depth = d1;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
bool getClosestPoints(b3GjkPairDetector* gjkDetector, const b3Transform& transA, const b3Transform& transB,
|
|
||||||
const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesA,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesB,
|
|
||||||
b3Scalar maximumDistanceSquared,
|
|
||||||
b3Vector3& resultSepNormal,
|
|
||||||
float& resultSepDistance,
|
|
||||||
b3Vector3& resultPointOnB)
|
|
||||||
{
|
|
||||||
//resultSepDistance = maximumDistanceSquared;
|
|
||||||
|
|
||||||
gjkDetector->m_cachedSeparatingDistance = 0.f;
|
|
||||||
|
|
||||||
b3Scalar distance=b3Scalar(0.);
|
|
||||||
b3Vector3 normalInB= b3MakeVector3(b3Scalar(0.),b3Scalar(0.),b3Scalar(0.));
|
|
||||||
b3Vector3 pointOnA,pointOnB;
|
|
||||||
|
|
||||||
b3Transform localTransA = transA;
|
|
||||||
b3Transform localTransB = transB;
|
|
||||||
|
|
||||||
b3Vector3 positionOffset = b3MakeVector3(0,0,0);// = (localTransA.getOrigin() + localTransB.getOrigin()) * b3Scalar(0.5);
|
|
||||||
localTransA.getOrigin() -= positionOffset;
|
|
||||||
localTransB.getOrigin() -= positionOffset;
|
|
||||||
|
|
||||||
bool check2d = false;//m_minkowskiA->isConvex2d() && m_minkowskiB->isConvex2d();
|
|
||||||
|
|
||||||
b3Scalar marginA = 0.f;//m_marginA;
|
|
||||||
b3Scalar marginB = 0.f;//m_marginB;
|
|
||||||
|
|
||||||
gNumGjkChecks2++;
|
|
||||||
|
|
||||||
|
|
||||||
//for CCD we don't use margins
|
|
||||||
if (gjkDetector->m_ignoreMargin)
|
|
||||||
{
|
|
||||||
marginA = b3Scalar(0.);
|
|
||||||
marginB = b3Scalar(0.);
|
|
||||||
}
|
|
||||||
|
|
||||||
gjkDetector->m_curIter = 0;
|
|
||||||
int gGjkMaxIter = 1000;//this is to catch invalid input, perhaps check for #NaN?
|
|
||||||
gjkDetector->m_cachedSeparatingAxis.setValue(1,1,1);//0,0,0);
|
|
||||||
|
|
||||||
bool isValid = false;
|
|
||||||
bool checkSimplex = false;
|
|
||||||
bool checkPenetration = true;
|
|
||||||
gjkDetector->m_degenerateSimplex = 0;
|
|
||||||
|
|
||||||
gjkDetector->m_lastUsedMethod = -1;
|
|
||||||
|
|
||||||
{
|
|
||||||
b3Scalar squaredDistance = B3_LARGE_FLOAT;
|
|
||||||
b3Scalar delta = -1e30f;//b3Scalar(0.);
|
|
||||||
// b3Scalar prevDelta = -1e30f;//b3Scalar(0.);
|
|
||||||
|
|
||||||
b3Scalar margin = marginA + marginB;
|
|
||||||
// b3Scalar bestDeltaN = -1e30f;
|
|
||||||
// b3Vector3 bestSepAxis= b3MakeVector3(0,0,0);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
gjkDetector->m_simplexSolver->reset();
|
|
||||||
|
|
||||||
for ( ; ; )
|
|
||||||
//while (true)
|
|
||||||
{
|
|
||||||
|
|
||||||
|
|
||||||
b3Vector3 seperatingAxisInA = (-gjkDetector->m_cachedSeparatingAxis)* localTransA.getBasis();
|
|
||||||
b3Vector3 seperatingAxisInB = gjkDetector->m_cachedSeparatingAxis* localTransB.getBasis();
|
|
||||||
|
|
||||||
b3Vector3 pInA = localGetSupportVertexWithoutMargin(seperatingAxisInA,&hullA,verticesA);
|
|
||||||
b3Vector3 qInB = localGetSupportVertexWithoutMargin(seperatingAxisInB,&hullB,verticesB);
|
|
||||||
|
|
||||||
b3Vector3 pWorld = localTransA(pInA);
|
|
||||||
b3Vector3 qWorld = localTransB(qInB);
|
|
||||||
|
|
||||||
|
|
||||||
#ifdef DEBUG_SPU_COLLISION_DETECTION
|
|
||||||
spu_printf("got local supporting vertices\n");
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (check2d)
|
|
||||||
{
|
|
||||||
pWorld[2] = 0.f;
|
|
||||||
qWorld[2] = 0.f;
|
|
||||||
}
|
|
||||||
|
|
||||||
b3Vector3 w = pWorld - qWorld;
|
|
||||||
delta = gjkDetector->m_cachedSeparatingAxis.dot(w);
|
|
||||||
|
|
||||||
// potential exit, they don't overlap
|
|
||||||
if ((delta > b3Scalar(0.0)) && (delta * delta > squaredDistance * maximumDistanceSquared))
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 10;
|
|
||||||
checkSimplex=true;
|
|
||||||
//checkPenetration = false;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
//exit 0: the new point is already in the simplex, or we didn't come any closer
|
|
||||||
if (gjkDetector->m_simplexSolver->inSimplex(w))
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 1;
|
|
||||||
checkSimplex = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
// are we getting any closer ?
|
|
||||||
b3Scalar f0 = squaredDistance - delta;
|
|
||||||
b3Scalar f1 = squaredDistance * REL_ERROR2;
|
|
||||||
|
|
||||||
if (f0 <= f1)
|
|
||||||
{
|
|
||||||
if (f0 <= b3Scalar(0.))
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 2;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 11;
|
|
||||||
}
|
|
||||||
checkSimplex = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef DEBUG_SPU_COLLISION_DETECTION
|
|
||||||
spu_printf("addVertex 1\n");
|
|
||||||
#endif
|
|
||||||
//add current vertex to simplex
|
|
||||||
gjkDetector->m_simplexSolver->addVertex(w, pWorld, qWorld);
|
|
||||||
#ifdef DEBUG_SPU_COLLISION_DETECTION
|
|
||||||
spu_printf("addVertex 2\n");
|
|
||||||
#endif
|
|
||||||
b3Vector3 newCachedSeparatingAxis;
|
|
||||||
|
|
||||||
//calculate the closest point to the origin (update vector v)
|
|
||||||
if (!gjkDetector->m_simplexSolver->closest(newCachedSeparatingAxis))
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 3;
|
|
||||||
checkSimplex = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(newCachedSeparatingAxis.length2()<REL_ERROR2)
|
|
||||||
{
|
|
||||||
gjkDetector->m_cachedSeparatingAxis = newCachedSeparatingAxis;
|
|
||||||
gjkDetector->m_degenerateSimplex = 6;
|
|
||||||
checkSimplex = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
b3Scalar previousSquaredDistance = squaredDistance;
|
|
||||||
squaredDistance = newCachedSeparatingAxis.length2();
|
|
||||||
#if 0
|
|
||||||
///warning: this termination condition leads to some problems in 2d test case see Bullet/Demos/Box2dDemo
|
|
||||||
if (squaredDistance>previousSquaredDistance)
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 7;
|
|
||||||
squaredDistance = previousSquaredDistance;
|
|
||||||
checkSimplex = false;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif //
|
|
||||||
|
|
||||||
|
|
||||||
//redundant gjkDetector->m_simplexSolver->compute_points(pointOnA, pointOnB);
|
|
||||||
|
|
||||||
//are we getting any closer ?
|
|
||||||
if (previousSquaredDistance - squaredDistance <= B3_EPSILON * previousSquaredDistance)
|
|
||||||
{
|
|
||||||
// gjkDetector->m_simplexSolver->backup_closest(gjkDetector->m_cachedSeparatingAxis);
|
|
||||||
checkSimplex = true;
|
|
||||||
gjkDetector->m_degenerateSimplex = 12;
|
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
gjkDetector->m_cachedSeparatingAxis = newCachedSeparatingAxis;
|
|
||||||
|
|
||||||
//degeneracy, this is typically due to invalid/uninitialized worldtransforms for a btCollisionObject
|
|
||||||
if (gjkDetector->m_curIter++ > gGjkMaxIter)
|
|
||||||
{
|
|
||||||
#if defined(DEBUG) || defined (_DEBUG) || defined (DEBUG_SPU_COLLISION_DETECTION)
|
|
||||||
|
|
||||||
printf("btGjkPairDetector maxIter exceeded:%i\n",gjkDetector->m_curIter);
|
|
||||||
printf("sepAxis=(%f,%f,%f), squaredDistance = %f\n",
|
|
||||||
gjkDetector->m_cachedSeparatingAxis.getX(),
|
|
||||||
gjkDetector->m_cachedSeparatingAxis.getY(),
|
|
||||||
gjkDetector->m_cachedSeparatingAxis.getZ(),
|
|
||||||
squaredDistance);
|
|
||||||
|
|
||||||
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
bool check = (!gjkDetector->m_simplexSolver->fullSimplex());
|
|
||||||
//bool check = (!gjkDetector->m_simplexSolver->fullSimplex() && squaredDistance > B3_EPSILON * gjkDetector->m_simplexSolver->maxVertex());
|
|
||||||
|
|
||||||
if (!check)
|
|
||||||
{
|
|
||||||
//do we need this backup_closest here ?
|
|
||||||
// gjkDetector->m_simplexSolver->backup_closest(gjkDetector->m_cachedSeparatingAxis);
|
|
||||||
gjkDetector->m_degenerateSimplex = 13;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (checkSimplex)
|
|
||||||
{
|
|
||||||
gjkDetector->m_simplexSolver->compute_points(pointOnA, pointOnB);
|
|
||||||
normalInB = gjkDetector->m_cachedSeparatingAxis;
|
|
||||||
b3Scalar lenSqr =gjkDetector->m_cachedSeparatingAxis.length2();
|
|
||||||
|
|
||||||
//valid normal
|
|
||||||
if (lenSqr < 0.0001)
|
|
||||||
{
|
|
||||||
gjkDetector->m_degenerateSimplex = 5;
|
|
||||||
}
|
|
||||||
if (lenSqr > B3_EPSILON*B3_EPSILON)
|
|
||||||
{
|
|
||||||
b3Scalar rlen = b3Scalar(1.) / b3Sqrt(lenSqr );
|
|
||||||
normalInB *= rlen; //normalize
|
|
||||||
b3Scalar s = b3Sqrt(squaredDistance);
|
|
||||||
|
|
||||||
b3Assert(s > b3Scalar(0.0));
|
|
||||||
pointOnA -= gjkDetector->m_cachedSeparatingAxis * (marginA / s);
|
|
||||||
pointOnB += gjkDetector->m_cachedSeparatingAxis * (marginB / s);
|
|
||||||
distance = ((b3Scalar(1.)/rlen) - margin);
|
|
||||||
isValid = true;
|
|
||||||
|
|
||||||
gjkDetector->m_lastUsedMethod = 1;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
gjkDetector->m_lastUsedMethod = 2;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool catchDegeneratePenetrationCase =
|
|
||||||
(gjkDetector->m_catchDegeneracies && gjkDetector->m_penetrationDepthSolver && gjkDetector->m_degenerateSimplex && ((distance+margin) < 0.01));
|
|
||||||
|
|
||||||
//if (checkPenetration && !isValid)
|
|
||||||
if (checkPenetration && (!isValid || catchDegeneratePenetrationCase ))
|
|
||||||
{
|
|
||||||
//penetration case
|
|
||||||
|
|
||||||
//if there is no way to handle penetrations, bail out
|
|
||||||
if (gjkDetector->m_penetrationDepthSolver)
|
|
||||||
{
|
|
||||||
// Penetration depth case.
|
|
||||||
b3Vector3 tmpPointOnA,tmpPointOnB;
|
|
||||||
|
|
||||||
gNumDeepPenetrationChecks2++;
|
|
||||||
gjkDetector->m_cachedSeparatingAxis.setZero();
|
|
||||||
|
|
||||||
bool isValid2 = calcPenDepth(
|
|
||||||
*gjkDetector->m_simplexSolver,
|
|
||||||
transA,transB,hullA,hullB,verticesA,verticesB,
|
|
||||||
gjkDetector->m_cachedSeparatingAxis, tmpPointOnA, tmpPointOnB
|
|
||||||
);
|
|
||||||
|
|
||||||
|
|
||||||
if (isValid2)
|
|
||||||
{
|
|
||||||
b3Vector3 tmpNormalInB = tmpPointOnB-tmpPointOnA;
|
|
||||||
b3Scalar lenSqr = tmpNormalInB.length2();
|
|
||||||
if (lenSqr <= (B3_EPSILON*B3_EPSILON))
|
|
||||||
{
|
|
||||||
tmpNormalInB = gjkDetector->m_cachedSeparatingAxis;
|
|
||||||
lenSqr = gjkDetector->m_cachedSeparatingAxis.length2();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (lenSqr > (B3_EPSILON*B3_EPSILON))
|
|
||||||
{
|
|
||||||
tmpNormalInB /= b3Sqrt(lenSqr);
|
|
||||||
b3Scalar distance2 = -(tmpPointOnA-tmpPointOnB).length();
|
|
||||||
//only replace valid penetrations when the result is deeper (check)
|
|
||||||
if (!isValid || (distance2 < distance))
|
|
||||||
{
|
|
||||||
distance = distance2;
|
|
||||||
pointOnA = tmpPointOnA;
|
|
||||||
pointOnB = tmpPointOnB;
|
|
||||||
normalInB = tmpNormalInB;
|
|
||||||
isValid = true;
|
|
||||||
gjkDetector->m_lastUsedMethod = 3;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
gjkDetector->m_lastUsedMethod = 8;
|
|
||||||
}
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
gjkDetector->m_lastUsedMethod = 9;
|
|
||||||
}
|
|
||||||
} else
|
|
||||||
|
|
||||||
{
|
|
||||||
///this is another degenerate case, where the initial GJK calculation reports a degenerate case
|
|
||||||
///EPA reports no penetration, and the second GJK (using the supporting vector without margin)
|
|
||||||
///reports a valid positive distance. Use the results of the second GJK instead of failing.
|
|
||||||
///thanks to Jacob.Langford for the reproduction case
|
|
||||||
///http://code.google.com/p/bullet/issues/detail?id=250
|
|
||||||
|
|
||||||
|
|
||||||
if (gjkDetector->m_cachedSeparatingAxis.length2() > b3Scalar(0.))
|
|
||||||
{
|
|
||||||
b3Scalar distance2 = (tmpPointOnA-tmpPointOnB).length()-margin;
|
|
||||||
//only replace valid distances when the distance is less
|
|
||||||
if (!isValid || (distance2 < distance))
|
|
||||||
{
|
|
||||||
distance = distance2;
|
|
||||||
pointOnA = tmpPointOnA;
|
|
||||||
pointOnB = tmpPointOnB;
|
|
||||||
pointOnA -= gjkDetector->m_cachedSeparatingAxis * marginA ;
|
|
||||||
pointOnB += gjkDetector->m_cachedSeparatingAxis * marginB ;
|
|
||||||
normalInB = gjkDetector->m_cachedSeparatingAxis;
|
|
||||||
normalInB.normalize();
|
|
||||||
isValid = true;
|
|
||||||
gjkDetector->m_lastUsedMethod = 6;
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
gjkDetector->m_lastUsedMethod = 5;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (isValid && (distance < 0))
|
|
||||||
//if (isValid && ((distance < 0) || (distance*distance < maximumDistanceSquared)))
|
|
||||||
{
|
|
||||||
|
|
||||||
if (1)//m_fixContactNormalDirection)
|
|
||||||
{
|
|
||||||
///@workaround for sticky convex collisions
|
|
||||||
//in some degenerate cases (usually when the use uses very small margins)
|
|
||||||
//the contact normal is pointing the wrong direction
|
|
||||||
//so fix it now (until we can deal with all degenerate cases in GJK and EPA)
|
|
||||||
//contact normals need to point from B to A in all cases, so we can simply check if the contact normal really points from B to A
|
|
||||||
//We like to use a dot product of the normal against the difference of the centroids,
|
|
||||||
//once the centroid is available in the API
|
|
||||||
//until then we use the center of the aabb to approximate the centroid
|
|
||||||
b3Vector3 posA = localTransA*hullA.m_localCenter;
|
|
||||||
b3Vector3 posB = localTransB*hullB.m_localCenter;
|
|
||||||
|
|
||||||
|
|
||||||
b3Vector3 diff = posA-posB;
|
|
||||||
if (diff.dot(normalInB) < 0.f)
|
|
||||||
normalInB *= -1.f;
|
|
||||||
}
|
|
||||||
gjkDetector->m_cachedSeparatingAxis = normalInB;
|
|
||||||
gjkDetector->m_cachedSeparatingDistance = distance;
|
|
||||||
|
|
||||||
/*output.addContactPoint(
|
|
||||||
normalInB,
|
|
||||||
pointOnB+positionOffset,
|
|
||||||
distance);
|
|
||||||
*/
|
|
||||||
|
|
||||||
static float maxPenetrationDistance = 0.f;
|
|
||||||
if (distance<maxPenetrationDistance)
|
|
||||||
{
|
|
||||||
maxPenetrationDistance = distance;
|
|
||||||
printf("maxPenetrationDistance = %f\n",maxPenetrationDistance);
|
|
||||||
}
|
|
||||||
resultSepNormal = normalInB;
|
|
||||||
resultSepDistance = distance;
|
|
||||||
resultPointOnB = pointOnB+positionOffset;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
return false;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -1,84 +0,0 @@
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#ifndef B3_GJK_PAIR_DETECTOR_H
|
|
||||||
#define B3_GJK_PAIR_DETECTOR_H
|
|
||||||
|
|
||||||
|
|
||||||
#include "Bullet3Common/b3Vector3.h"
|
|
||||||
#include "Bullet3Common/b3AlignedObjectArray.h"
|
|
||||||
|
|
||||||
class b3Transform;
|
|
||||||
struct b3GjkEpaSolver2;
|
|
||||||
class b3VoronoiSimplexSolver;
|
|
||||||
struct b3ConvexPolyhedronData;
|
|
||||||
|
|
||||||
B3_ATTRIBUTE_ALIGNED16(struct) b3GjkPairDetector
|
|
||||||
{
|
|
||||||
|
|
||||||
|
|
||||||
b3Vector3 m_cachedSeparatingAxis;
|
|
||||||
b3GjkEpaSolver2* m_penetrationDepthSolver;
|
|
||||||
b3VoronoiSimplexSolver* m_simplexSolver;
|
|
||||||
|
|
||||||
|
|
||||||
bool m_ignoreMargin;
|
|
||||||
b3Scalar m_cachedSeparatingDistance;
|
|
||||||
|
|
||||||
|
|
||||||
public:
|
|
||||||
|
|
||||||
//some debugging to fix degeneracy problems
|
|
||||||
int m_lastUsedMethod;
|
|
||||||
int m_curIter;
|
|
||||||
int m_degenerateSimplex;
|
|
||||||
int m_catchDegeneracies;
|
|
||||||
int m_fixContactNormalDirection;
|
|
||||||
|
|
||||||
b3GjkPairDetector(b3VoronoiSimplexSolver* simplexSolver,b3GjkEpaSolver2* penetrationDepthSolver);
|
|
||||||
|
|
||||||
virtual ~b3GjkPairDetector() {};
|
|
||||||
|
|
||||||
|
|
||||||
//void getClosestPoints(,Result& output);
|
|
||||||
|
|
||||||
void setCachedSeperatingAxis(const b3Vector3& seperatingAxis)
|
|
||||||
{
|
|
||||||
m_cachedSeparatingAxis = seperatingAxis;
|
|
||||||
}
|
|
||||||
|
|
||||||
const b3Vector3& getCachedSeparatingAxis() const
|
|
||||||
{
|
|
||||||
return m_cachedSeparatingAxis;
|
|
||||||
}
|
|
||||||
b3Scalar getCachedSeparatingDistance() const
|
|
||||||
{
|
|
||||||
return m_cachedSeparatingDistance;
|
|
||||||
}
|
|
||||||
|
|
||||||
void setPenetrationDepthSolver(b3GjkEpaSolver2* penetrationDepthSolver)
|
|
||||||
{
|
|
||||||
m_penetrationDepthSolver = penetrationDepthSolver;
|
|
||||||
}
|
|
||||||
|
|
||||||
///don't use setIgnoreMargin, it's for Bullet's internal use
|
|
||||||
void setIgnoreMargin(bool ignoreMargin)
|
|
||||||
{
|
|
||||||
m_ignoreMargin = ignoreMargin;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
bool getClosestPoints(b3GjkPairDetector* gjkDetector, const b3Transform& transA, const b3Transform& transB,
|
|
||||||
const b3ConvexPolyhedronData& hullA, const b3ConvexPolyhedronData& hullB,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesA,
|
|
||||||
const b3AlignedObjectArray<b3Vector3>& verticesB,
|
|
||||||
b3Scalar maximumDistanceSquared,
|
|
||||||
b3Vector3& resultSepNormal,
|
|
||||||
float& resultSepDistance,
|
|
||||||
b3Vector3& resultPointOnB);
|
|
||||||
|
|
||||||
#endif //B3_GJK_PAIR_DETECTOR_H
|
|
||||||
@@ -3003,6 +3003,7 @@ void btSoftBody::applyForces()
|
|||||||
//
|
//
|
||||||
void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti)
|
void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti)
|
||||||
{
|
{
|
||||||
|
BT_PROFILE("PSolve_Anchors");
|
||||||
const btScalar kAHR=psb->m_cfg.kAHR*kst;
|
const btScalar kAHR=psb->m_cfg.kAHR*kst;
|
||||||
const btScalar dt=psb->m_sst.sdt;
|
const btScalar dt=psb->m_sst.sdt;
|
||||||
for(int i=0,ni=psb->m_anchors.size();i<ni;++i)
|
for(int i=0,ni=psb->m_anchors.size();i<ni;++i)
|
||||||
@@ -3024,8 +3025,10 @@ void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti)
|
|||||||
//
|
//
|
||||||
void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti)
|
void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti)
|
||||||
{
|
{
|
||||||
|
BT_PROFILE("PSolve_RContacts");
|
||||||
const btScalar dt = psb->m_sst.sdt;
|
const btScalar dt = psb->m_sst.sdt;
|
||||||
const btScalar mrg = psb->getCollisionShape()->getMargin();
|
const btScalar mrg = psb->getCollisionShape()->getMargin();
|
||||||
|
btMultiBodyJacobianData jacobianData;
|
||||||
for(int i=0,ni=psb->m_rcontacts.size();i<ni;++i)
|
for(int i=0,ni=psb->m_rcontacts.size();i<ni;++i)
|
||||||
{
|
{
|
||||||
const RContact& c = psb->m_rcontacts[i];
|
const RContact& c = psb->m_rcontacts[i];
|
||||||
@@ -3033,10 +3036,10 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti)
|
|||||||
if (cti.m_colObj->hasContactResponse())
|
if (cti.m_colObj->hasContactResponse())
|
||||||
{
|
{
|
||||||
btVector3 va(0,0,0);
|
btVector3 va(0,0,0);
|
||||||
btRigidBody* rigidCol;
|
btRigidBody* rigidCol=0;
|
||||||
btMultiBodyLinkCollider* multibodyLinkCol;
|
btMultiBodyLinkCollider* multibodyLinkCol=0;
|
||||||
btScalar* deltaV;
|
btScalar* deltaV;
|
||||||
btMultiBodyJacobianData jacobianData;
|
|
||||||
if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY)
|
if (cti.m_colObj->getInternalType() == btCollisionObject::CO_RIGID_BODY)
|
||||||
{
|
{
|
||||||
rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj);
|
rigidCol = (btRigidBody*)btRigidBody::upcast(cti.m_colObj);
|
||||||
@@ -3096,6 +3099,8 @@ void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti)
|
|||||||
//
|
//
|
||||||
void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti)
|
void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti)
|
||||||
{
|
{
|
||||||
|
BT_PROFILE("PSolve_SContacts");
|
||||||
|
|
||||||
for(int i=0,ni=psb->m_scontacts.size();i<ni;++i)
|
for(int i=0,ni=psb->m_scontacts.size();i<ni;++i)
|
||||||
{
|
{
|
||||||
const SContact& c=psb->m_scontacts[i];
|
const SContact& c=psb->m_scontacts[i];
|
||||||
@@ -3129,6 +3134,7 @@ void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti)
|
|||||||
//
|
//
|
||||||
void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti)
|
void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti)
|
||||||
{
|
{
|
||||||
|
BT_PROFILE("PSolve_Links");
|
||||||
for(int i=0,ni=psb->m_links.size();i<ni;++i)
|
for(int i=0,ni=psb->m_links.size();i<ni;++i)
|
||||||
{
|
{
|
||||||
Link& l=psb->m_links[i];
|
Link& l=psb->m_links[i];
|
||||||
@@ -3151,6 +3157,7 @@ void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti)
|
|||||||
//
|
//
|
||||||
void btSoftBody::VSolve_Links(btSoftBody* psb,btScalar kst)
|
void btSoftBody::VSolve_Links(btSoftBody* psb,btScalar kst)
|
||||||
{
|
{
|
||||||
|
BT_PROFILE("VSolve_Links");
|
||||||
for(int i=0,ni=psb->m_links.size();i<ni;++i)
|
for(int i=0,ni=psb->m_links.size();i<ni;++i)
|
||||||
{
|
{
|
||||||
Link& l=psb->m_links[i];
|
Link& l=psb->m_links[i];
|
||||||
|
|||||||
Reference in New Issue
Block a user