diff --git a/examples/MultiBody/MultiDofDemo.cpp b/examples/MultiBody/MultiDofDemo.cpp index e4e3ba66f..d0530f9fb 100644 --- a/examples/MultiBody/MultiDofDemo.cpp +++ b/examples/MultiBody/MultiDofDemo.cpp @@ -148,6 +148,7 @@ void MultiDofDemo::initPhysics() // m_dynamicsWorld->setDebugDrawer(&gDebugDraw); m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); m_dynamicsWorld->setGravity(btVector3(0,-10,0)); + m_dynamicsWorld->getSolverInfo().m_globalCfm = 1e-3; ///create a few basic rigid bodies btVector3 groundHalfExtents(50,50,50); @@ -169,7 +170,7 @@ void MultiDofDemo::initPhysics() int numLinks = 5; bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals bool multibodyOnly = false; - bool canSleep = true; + bool canSleep = false; bool selfCollide = true; bool multibodyConstraint = false; btVector3 linkHalfExtents(0.05, 0.37, 0.1); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 80a3c695d..d8d6cd789 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2381,7 +2381,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08; m_data->m_dynamicsWorld->getSolverInfo().m_frictionERP = 0.2;//need to check if there are artifacts with frictionERP - m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0; + m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50; m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7; // m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2; diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index b4ab56487..52f7b05b8 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -327,7 +327,7 @@ void b3PluginManager::reportNotifications() plugin->m_processNotificationsFunc(&context); } } - notifications.clear(); + notifications.resize(0); } int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArguments* arguments) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index cae7bb816..ff92f8929 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -8529,10 +8529,10 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self, { int szInBytes = sizeof(double) * szJointDamping; int i; - if (szJointDamping != dofCount) - { - printf("calculateInverseKinematics: the size of input joint damping values should be equal to the number of degrees of freedom, ignoring the additonal values."); - } + //if (szJointDamping != dofCount) + //{ + // printf("calculateInverseKinematics: the size of input joint damping values should be equal to the number of degrees of freedom, ignoring the additonal values."); + //} jointDamping = (double*)malloc(szInBytes); for (i = 0; i < szJointDamping; i++) { diff --git a/setup.py b/setup.py index cfea0b36b..a660aeb04 100644 --- a/setup.py +++ b/setup.py @@ -453,7 +453,7 @@ print("-----") setup( name = 'pybullet', - version='2.0.9', + version='2.1.2', 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.', url='https://github.com/bulletphysics/bullet3',