PyBullet: expose internal edge utility, to adjust edge normals to prevent object penetrating along triangle edges of concave triangle meshes
(due to local convex-triangle collisions causing opposite contact normals, use the pre-computed edge normal) PyBullet: expose experimental continuous collision detection for maximal coordinate rigid bodies, to prevent tunneling.
This commit is contained in:
@@ -6,6 +6,8 @@
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btInternalEdgeUtility.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
@@ -1727,6 +1729,7 @@ void logCallback(btDynamicsWorld *world, btScalar timeStep)
|
||||
|
||||
bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||
{
|
||||
btAdjustInternalEdgeContacts(cp, colObj1Wrap, colObj0Wrap, partId1,index1);
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -2253,12 +2256,13 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
||||
isPreTick = true;
|
||||
m_data->m_dynamicsWorld->setInternalTickCallback(preTickCallback,this,isPreTick);
|
||||
|
||||
gContactAddedCallback = MyContactAddedCallback;
|
||||
|
||||
#ifdef B3_ENABLE_TINY_AUDIO
|
||||
m_data->m_soundEngine.init(16,true);
|
||||
|
||||
//we don't use those callbacks (yet), experimental
|
||||
// gContactAddedCallback = MyContactAddedCallback;
|
||||
|
||||
// gContactDestroyedCallback = MyContactDestroyedCallback;
|
||||
// gContactProcessedCallback = MyContactProcessedCallback;
|
||||
// gContactStartedCallback = MyContactStartedCallback;
|
||||
@@ -2411,6 +2415,17 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
|
||||
for (int j = 0; j<m_data->m_collisionShapes.size(); j++)
|
||||
{
|
||||
btCollisionShape* shape = m_data->m_collisionShapes[j];
|
||||
|
||||
|
||||
//check for internal edge utility, delete memory
|
||||
if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*) shape;
|
||||
if (trimesh->getTriangleInfoMap())
|
||||
{
|
||||
delete trimesh->getTriangleInfoMap();
|
||||
}
|
||||
}
|
||||
delete shape;
|
||||
}
|
||||
for (int j=0;j<m_data->m_meshInterfaces.size();j++)
|
||||
@@ -3823,10 +3838,17 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
|
||||
meshInterface->addTriangle(v0, v1, v2);
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
BT_PROFILE("create btBvhTriangleMeshShape");
|
||||
btBvhTriangleMeshShape* trimesh = new btBvhTriangleMeshShape(meshInterface, true, true);
|
||||
m_data->m_collisionShapes.push_back(trimesh);
|
||||
|
||||
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_CONCAVE_INTERNAL_EDGE)
|
||||
{
|
||||
btTriangleInfoMap* triangleInfoMap = new btTriangleInfoMap();
|
||||
btGenerateInternalEdgeInfo(trimesh, triangleInfoMap);
|
||||
}
|
||||
//trimesh->setLocalScaling(collision->m_geometry.m_meshScale);
|
||||
shape = trimesh;
|
||||
if (compound)
|
||||
@@ -6377,6 +6399,13 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
|
||||
body->m_rigidBody->setMassProps(mass,newLocalInertiaDiagonal);
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_CCD_SWEPT_SPHERE_RADIUS)
|
||||
{
|
||||
body->m_rigidBody->setCcdSweptSphereRadius(clientCmd.m_changeDynamicsInfoArgs.m_ccdSweptSphereRadius);
|
||||
//for a given sphere radius, use a motion threshold of half the radius, before the ccd algorithm is enabled
|
||||
body->m_rigidBody->setCcdMotionThreshold(clientCmd.m_changeDynamicsInfoArgs.m_ccdSweptSphereRadius/2.);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6534,6 +6563,12 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
|
||||
{
|
||||
m_data->m_dynamicsWorld->getDispatchInfo().m_deterministicOverlappingPairs = (clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs!=0);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION)
|
||||
{
|
||||
m_data->m_dynamicsWorld->getDispatchInfo().m_allowedCcdPenetration = clientCmd.m_physSimParamArgs.m_allowedCcdPenetration;
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
|
||||
{
|
||||
m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
|
||||
|
||||
Reference in New Issue
Block a user