Add preliminary PhysX 4.0 backend for PyBullet

Add inverse dynamics / mass matrix code from DeepMimic, thanks to Xue Bin (Jason) Peng
Add example how to use stable PD control for humanoid with spherical joints (see humanoidMotionCapture.py)
Fix related to TinyRenderer object transforms not updating when using collision filtering
This commit is contained in:
erwincoumans
2019-01-22 21:08:37 -08:00
parent 80684f44ea
commit ae8e83988b
366 changed files with 131855 additions and 359 deletions

View File

@@ -43,6 +43,7 @@ btCollisionObject::btCollisionObject()
m_userObjectPointer(0),
m_userIndex2(-1),
m_userIndex(-1),
m_userIndex3(-1),
m_hitFraction(btScalar(1.)),
m_ccdSweptSphereRadius(btScalar(0.)),
m_ccdMotionThreshold(btScalar(0.)),

View File

@@ -101,6 +101,8 @@ protected:
int m_userIndex;
int m_userIndex3;
///time of impact calculation
btScalar m_hitFraction;
@@ -526,6 +528,11 @@ public:
return m_userIndex2;
}
int getUserIndex3() const
{
return m_userIndex3;
}
///users can point to their objects, userPointer is not used by Bullet
void setUserPointer(void* userPointer)
{
@@ -543,6 +550,11 @@ public:
m_userIndex2 = index;
}
void setUserIndex3(int index)
{
m_userIndex3 = index;
}
int getUpdateRevisionInternal() const
{
return m_updateRevision;