diff --git a/data/gripper/wsg50_one_motor_gripper_new.sdf b/data/gripper/wsg50_one_motor_gripper_new.sdf
index 5bb80d6a6..54f469fe0 100644
--- a/data/gripper/wsg50_one_motor_gripper_new.sdf
+++ b/data/gripper/wsg50_one_motor_gripper_new.sdf
@@ -303,6 +303,10 @@
+
+ .3
+ 0.04
+
0.062 0 0.145 0 0 1.5708
0.2
@@ -343,6 +347,10 @@
+
+ .3
+ 0.04
+
-0.062 0 0.145 0 0 4.71239
0.2
diff --git a/data/sphere_1cm.urdf b/data/sphere_1cm.urdf
index b44069877..05a07cde7 100644
--- a/data/sphere_1cm.urdf
+++ b/data/sphere_1cm.urdf
@@ -2,23 +2,15 @@
-
-
+
+
-
-
-
-
-
-
-
-
-
+
diff --git a/examples/CommonInterfaces/CommonExampleInterface.h b/examples/CommonInterfaces/CommonExampleInterface.h
index df5f1817e..fd0b2651a 100644
--- a/examples/CommonInterfaces/CommonExampleInterface.h
+++ b/examples/CommonInterfaces/CommonExampleInterface.h
@@ -37,6 +37,7 @@ public:
virtual void initPhysics()=0;
virtual void exitPhysics()=0;
+ virtual void updateGraphics(){}
virtual void stepSimulation(float deltaTime)=0;
virtual void renderScene()=0;
virtual void physicsDebugDraw(int debugFlags)=0;//for now we reuse the flags in Bullet/src/LinearMath/btIDebugDraw.h
diff --git a/examples/ExampleBrowser/InProcessExampleBrowser.cpp b/examples/ExampleBrowser/InProcessExampleBrowser.cpp
index 0b979b361..88a2abd99 100644
--- a/examples/ExampleBrowser/InProcessExampleBrowser.cpp
+++ b/examples/ExampleBrowser/InProcessExampleBrowser.cpp
@@ -266,6 +266,7 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
{
B3_PROFILE("clock.usleep");
clock.usleep(gMinUpdateTimeMicroSecs/10.);
+ exampleBrowser->updateGraphics();
} else
{
B3_PROFILE("exampleBrowser->update");
diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp
index fb13df898..65464268c 100644
--- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp
+++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp
@@ -309,8 +309,11 @@ static void MyMouseMoveCallback( float x, float y)
bool handled = false;
if (sCurrentDemo)
handled = sCurrentDemo->mouseMoveCallback(x,y);
- if (!handled && gui2)
- handled = gui2->mouseMoveCallback(x,y);
+ if (renderGui)
+ {
+ if (!handled && gui2)
+ handled = gui2->mouseMoveCallback(x,y);
+ }
if (!handled)
{
if (prevMouseMoveCallback)
@@ -327,9 +330,11 @@ static void MyMouseButtonCallback(int button, int state, float x, float y)
if (sCurrentDemo)
handled = sCurrentDemo->mouseButtonCallback(button,state,x,y);
- if (!handled && gui2)
- handled = gui2->mouseButtonCallback(button,state,x,y);
-
+ if (renderGui)
+ {
+ if (!handled && gui2)
+ handled = gui2->mouseButtonCallback(button,state,x,y);
+ }
if (!handled)
{
if (prevMouseButtonCallback )
@@ -1125,6 +1130,18 @@ bool OpenGLExampleBrowser::requestedExit()
return s_window->requestedExit();
}
+void OpenGLExampleBrowser::updateGraphics()
+{
+ if (sCurrentDemo)
+ {
+ if (!pauseSimulation || singleStepSimulation)
+ {
+ B3_PROFILE("sCurrentDemo->updateGraphics");
+ sCurrentDemo->updateGraphics();
+ }
+ }
+}
+
void OpenGLExampleBrowser::update(float deltaTime)
{
b3ChromeUtilsEnableProfiling();
diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.h b/examples/ExampleBrowser/OpenGLExampleBrowser.h
index 1f68abedb..533b666ff 100644
--- a/examples/ExampleBrowser/OpenGLExampleBrowser.h
+++ b/examples/ExampleBrowser/OpenGLExampleBrowser.h
@@ -19,6 +19,8 @@ public:
virtual void update(float deltaTime);
+ virtual void updateGraphics();
+
virtual bool requestedExit();
virtual void setSharedMemoryInterface(class SharedMemoryInterface* sharedMem);
diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
index 30b2d90f4..30f35963a 100644
--- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
+++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
@@ -71,7 +71,7 @@ struct URDF2BulletCachedData
}
- void registerMultiBody( int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
+ void registerMultiBody( int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame)
{
m_urdfLinkLocalInertialFrames[urdfLinkIndex] = localInertialFrame;
}
@@ -81,7 +81,7 @@ struct URDF2BulletCachedData
return m_urdfLink2rigidBodies[urdfLinkIndex];
}
- void registerRigidBody( int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
+ void registerRigidBody( int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame)
{
btAssert(m_urdfLink2rigidBodies[urdfLinkIndex]==0);
@@ -250,7 +250,12 @@ void ConvertURDF2BulletInternal(
- btCompoundShape* compoundShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
+ btCompoundShape* tmpShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
+ btCollisionShape* compoundShape = tmpShape;
+ if (tmpShape->getNumChildShapes() == 1 && tmpShape->getChildTransform(0)==btTransform::getIdentity())
+ {
+ compoundShape = tmpShape->getChildShape(0);
+ }
int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp
index e7c51fe15..212d80a6f 100644
--- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp
+++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp
@@ -787,7 +787,7 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName)
#ifdef _WIN32
sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
- "-threads 0 -y -b 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName);
+ "-threads 0 -y -b:v 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName);
//sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
// "-y -crf 0 -b:v 1500000 -an -vcodec h264 -vf vflip %s", width, height, mp4FileName);
diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp
index 4b86a567d..5dbbd1562 100644
--- a/examples/RoboticsLearning/GripperGraspExample.cpp
+++ b/examples/RoboticsLearning/GripperGraspExample.cpp
@@ -16,8 +16,8 @@
#include "b3RobotSimAPI.h"
#include "../Utils/b3Clock.h"
-static btScalar sGripperVerticalVelocity = -0.2f;
-static btScalar sGripperClosingTargetVelocity = 0.5f;
+static btScalar sGripperVerticalVelocity = 0.f;
+static btScalar sGripperClosingTargetVelocity = -0.7f;
class GripperGraspExample : public CommonExampleInterface
{
@@ -226,9 +226,9 @@ public:
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
- args.m_fileName = "sphere_small.urdf";
- args.m_startPosition.setValue(0, 0, .107);
- args.m_startOrientation.setEulerZYX(0, 0, 0);
+ args.m_fileName = "dinnerware/pan_tefal.urdf";
+ args.m_startPosition.setValue(0, -0.2, .47);
+ args.m_startOrientation.setEulerZYX(SIMD_HALF_PI, 0, 0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
}
@@ -492,7 +492,7 @@ public:
int fingerJointIndices[2]={0,1};
double fingerTargetVelocities[2]={sGripperVerticalVelocity,sGripperClosingTargetVelocity
};
- double maxTorqueValues[2]={50.0,50.0};
+ double maxTorqueValues[2]={800.0,800.0};
for (int i=0;i<2;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
@@ -550,8 +550,8 @@ public:
virtual void resetCamera()
{
float dist = 1.5;
- float pitch = 12;
- float yaw = -10;
+ float pitch = 18;
+ float yaw = 10;
float targetPos[3]={-0.2,0.8,0.3};
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
{
diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp
index f02e332a4..e311cff08 100644
--- a/examples/SharedMemory/PhysicsClientC_API.cpp
+++ b/examples/SharedMemory/PhysicsClientC_API.cpp
@@ -338,6 +338,16 @@ int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandl
return 0;
}
+int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold)
+{
+ struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
+ b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
+
+ command->m_physSimParamArgs.m_contactBreakingThreshold = contactBreakingThreshold;
+ command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD;
+ return 0;
+}
+
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h
index febe08396..b150e54d7 100644
--- a/examples/SharedMemory/PhysicsClientC_API.h
+++ b/examples/SharedMemory/PhysicsClientC_API.h
@@ -191,7 +191,7 @@ int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHand
int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
-
+int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index cd4260469..75271eb37 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -12,6 +12,7 @@
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
+#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "LinearMath/btHashMap.h"
#include "BulletInverseDynamics/MultiBodyTree.hpp"
#include "IKTrajectoryHelper.h"
@@ -798,7 +799,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
- m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
+ m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 150;
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;
// m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2;
//todo: islands/constraints are buggy in btMultiBodyDynamicsWorld! (performance + see slipping grasp)
@@ -2724,7 +2725,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
}
-
+ if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD)
+ {
+ gContactBreakingThreshold = clientCmd.m_physSimParamArgs.m_contactBreakingThreshold;
+ }
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE)
{
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = clientCmd.m_physSimParamArgs.m_collisionFilterMode;
diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp
index 4c9ae62fe..520a6d904 100644
--- a/examples/SharedMemory/PhysicsServerExample.cpp
+++ b/examples/SharedMemory/PhysicsServerExample.cpp
@@ -553,7 +553,7 @@ public:
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
- b3Clock::usleep(100);
+ b3Clock::usleep(0);
}
}
@@ -940,6 +940,8 @@ public:
virtual void stepSimulation(float deltaTime);
+ virtual void updateGraphics();
+
void enableCommandLogging()
{
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
@@ -1342,39 +1344,8 @@ bool PhysicsServerExample::wantsTermination()
return m_wantsShutdown;
}
-
-
-void PhysicsServerExample::stepSimulation(float deltaTime)
+void PhysicsServerExample::updateGraphics()
{
- BT_PROFILE("PhysicsServerExample::stepSimulation");
-
- //this->m_physicsServer.processClientCommands();
-
- for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
- {
- if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
- {
- m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
- if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
- {
- m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
- m_multiThreadedHelper->m_userDebugLines.pop_back();
- }
- }
- }
-
- for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
- {
- if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
- {
- m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
- if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
- {
- m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
- m_multiThreadedHelper->m_userDebugText.pop_back();
- }
- }
- }
//check if any graphics related tasks are requested
switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
@@ -1543,6 +1514,40 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
}
+}
+
+void PhysicsServerExample::stepSimulation(float deltaTime)
+{
+ BT_PROFILE("PhysicsServerExample::stepSimulation");
+
+ //this->m_physicsServer.processClientCommands();
+
+ for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
+ {
+ if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
+ {
+ m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
+ if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
+ {
+ m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
+ m_multiThreadedHelper->m_userDebugLines.pop_back();
+ }
+ }
+ }
+
+ for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
+ {
+ if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
+ {
+ m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
+ if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
+ {
+ m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
+ m_multiThreadedHelper->m_userDebugText.pop_back();
+ }
+ }
+ }
+ updateGraphics();
diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h
index 847a0de75..94d8b6a9c 100644
--- a/examples/SharedMemory/SharedMemoryCommands.h
+++ b/examples/SharedMemory/SharedMemoryCommands.h
@@ -313,7 +313,8 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64,
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE=128,
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256,
- SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512
+ SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
+ SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
};
enum EnumLoadBunnyUpdateFlags
@@ -340,6 +341,7 @@ struct SendPhysicsSimulationParameters
bool m_allowRealTimeSimulation;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
+ double m_contactBreakingThreshold;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;
diff --git a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
index b4933aeb4..f1a4b4966 100644
--- a/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
+++ b/examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
@@ -44,16 +44,13 @@ public:
PhysicsClientSharedMemory::disconnectSharedMemory();
}
unsigned long int ms = m_clock.getTimeMilliseconds();
- if (ms>20)
- {
- m_clock.reset();
- btUpdateInProcessExampleBrowserMainThread(m_data);
- } else
- {
- //b3Clock::usleep(100);
- }
- return PhysicsClientSharedMemory::processServerStatus();
-
+ if (ms>20)
+ {
+ m_clock.reset();
+ btUpdateInProcessExampleBrowserMainThread(m_data);
+ }
+ b3Clock::usleep(0);
+ return PhysicsClientSharedMemory::processServerStatus();
}
diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp
index 590312503..4c6b16ffe 100644
--- a/examples/StandaloneMain/hellovr_opengl_main.cpp
+++ b/examples/StandaloneMain/hellovr_opengl_main.cpp
@@ -135,6 +135,8 @@ public:
void SetupRenderModelForTrackedDevice( vr::TrackedDeviceIndex_t unTrackedDeviceIndex );
CGLRenderModel *FindOrLoadRenderModel( const char *pchRenderModelName );
+ SimpleOpenGL3App* getApp() { return m_app;}
+
private:
bool m_bDebugOpenGL;
bool m_bVerbose;
@@ -2260,7 +2262,7 @@ int main(int argc, char *argv[])
b3ChromeUtilsEnableProfiling();
}
-
+
#ifdef BT_USE_CUSTOM_PROFILER
b3SetCustomEnterProfileZoneFunc(dcEnter);
b3SetCustomLeaveProfileZoneFunc(dcLeave);
@@ -2287,6 +2289,11 @@ int main(int argc, char *argv[])
}
+ char* gVideoFileName = 0;
+ args.GetCmdLineArgument("mp4",gVideoFileName);
+ if (gVideoFileName)
+ pMainApplication->getApp()->dumpFramesToVideo(gVideoFileName);
+
//request disable VSYNC
typedef bool (APIENTRY *PFNWGLSWAPINTERVALFARPROC)(int);
PFNWGLSWAPINTERVALFARPROC wglSwapIntervalEXT = 0;
diff --git a/examples/pybullet/manyspheres.py b/examples/pybullet/manyspheres.py
index c06a477ab..1c4c37b97 100644
--- a/examples/pybullet/manyspheres.py
+++ b/examples/pybullet/manyspheres.py
@@ -7,9 +7,9 @@ p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
gravXid = p.addUserDebugParameter("gravityX",-10,10,0)
gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
-gravZid = p.addUserDebugParameter("gravityZ",-10,10,0)
+gravZid = p.addUserDebugParameter("gravityZ",-10,10,-10)
p.setPhysicsEngineParameter(numSolverIterations=10)
-
+p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
for i in range (10):
for j in range (10):
for k in range (5):
@@ -21,5 +21,5 @@ while True:
gravY = p.readUserDebugParameter(gravYid)
gravZ = p.readUserDebugParameter(gravZid)
p.setGravity(gravX,gravY,gravZ)
- time.sleep(1)
+ time.sleep(0.01)
diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c
index 65cc7e108..5b43cf6d7 100644
--- a/examples/pybullet/pybullet.c
+++ b/examples/pybullet/pybullet.c
@@ -583,14 +583,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
double splitImpulsePenetrationThreshold = -1;
int numSubSteps = -1;
int collisionFilterMode = -1;
+ double contactBreakingThreshold = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
- static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "physicsClientId", NULL };
+ static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "physicsClientId", NULL };
- if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
- &collisionFilterMode, &physicsClientId))
+ if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
+ &collisionFilterMode, &contactBreakingThreshold, &physicsClientId))
{
return NULL;
}
@@ -610,6 +611,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{
b3PhysicsParamSetNumSolverIterations(command, numSolverIterations);
}
+
if (collisionFilterMode>=0)
{
b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode);
@@ -630,6 +632,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{
b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold);
}
+ if (contactBreakingThreshold>=0)
+ {
+ b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold);
+ }
+
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);