Merge pull request #1727 from erwincoumans/master

PyBullet picking change, revert gjk test
This commit is contained in:
erwincoumans
2018-06-02 00:13:43 -07:00
committed by GitHub
7 changed files with 18 additions and 9 deletions

View File

@@ -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;
}

View File

@@ -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);
}
}

View File

@@ -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);

View File

@@ -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',

View File

@@ -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