diff --git a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp index 6ae5f4b7c..7bda1a949 100644 --- a/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp +++ b/examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp @@ -25,6 +25,8 @@ m_guiHelper(guiHelper) m_mb2urdfLink.resize(totalNumJoints+1,-2); m_bulletMultiBody = new btMultiBody(totalNumJoints,mass,localInertiaDiagonal,isFixedBase,canSleep); + //if (canSleep) + // m_bulletMultiBody->goToSleep(); return m_bulletMultiBody; } diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index 00f1f77ab..6e02c7b05 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -595,6 +595,11 @@ void ConvertURDF2BulletInternal( } } else { + //todo: fix the crash it can cause + //if (cache.m_bulletMultiBody->getBaseMass()==0) + //{ + // col->setCollisionFlags(btCollisionObject::CF_KINEMATIC_OBJECT);//:CF_STATIC_OBJECT); + //} cache.m_bulletMultiBody->setBaseCollider(col); } } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1376958c0..a3cb2bdf6 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -9904,4 +9904,4 @@ const btQuaternion& PhysicsServerCommandProcessor::getVRTeleportOrientation() co void PhysicsServerCommandProcessor::setVRTeleportOrientation(const btQuaternion& vrTeleportOrn) { gVRTeleportOrn = vrTeleportOrn; -} +} \ No newline at end of file diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index d6954e0b8..e6c367935 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -8166,14 +8166,16 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self, if (szJointDamping > 0) { - if (szJointDamping != dofCount) + if (szJointDamping < dofCount) { - PyErr_SetString(SpamError, - "calculateInverseKinematics the size of input joint damping values is unequal to the number of degrees of freedom."); - return NULL; + printf("calculateInverseKinematics: the size of input joint damping values should be equal to the number of degrees of freedom, not using joint damping."); } else { + 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."); + } int szInBytes = sizeof(double) * szJointDamping; int i; jointDamping = (double*)malloc(szInBytes); diff --git a/setup.py b/setup.py index 90c0875fe..570c95d9a 100644 --- a/setup.py +++ b/setup.py @@ -450,7 +450,7 @@ print("-----") setup( name = 'pybullet', - version='2.0.2', + version='2.0.3', 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', diff --git a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp index 01b73b537..4d29089a4 100644 --- a/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp +++ b/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp @@ -32,10 +32,10 @@ subject to the following restrictions: //must be above the machine epsilon #ifdef BT_USE_DOUBLE_PRECISION #define REL_ERROR2 btScalar(1.0e-12) - btScalar gGjkEpaPenetrationTolerance = BT_LARGE_FLOAT; + btScalar gGjkEpaPenetrationTolerance = 1.0e-12; #else #define REL_ERROR2 btScalar(1.0e-6) - btScalar gGjkEpaPenetrationTolerance = BT_LARGE_FLOAT; + btScalar gGjkEpaPenetrationTolerance = 0.001; #endif //temp globals, to improve GJK/EPA/penetration calculations diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index 8c6cb6aa8..c8f7fb0aa 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -1664,4 +1664,4 @@ void btMultiBodyConstraintSolver::solveMultiBodyGroup(btCollisionObject** bodie m_tmpNumMultiBodyConstraints = 0; -} +} \ No newline at end of file