expose gear erp/relative position target to C-API/pybullet

finish much better C++ vrSyncPlugin, running in-the-loop with the physics at high frequency, see also vr_kuka_setup_vrSyncPlugin.py
This commit is contained in:
erwincoumans
2017-09-26 19:54:36 -07:00
parent b1f8eb74a4
commit 8a265b8af2
12 changed files with 301 additions and 31 deletions

View File

@@ -28,10 +28,12 @@ protected:
btRigidBody* m_rigidBodyB;
btVector3 m_pivotInA;
btVector3 m_pivotInB;
btMatrix3x3 m_frameInA;
btMatrix3x3 m_frameInB;
btMatrix3x3 m_frameInA;
btMatrix3x3 m_frameInB;
btScalar m_gearRatio;
int m_gearAuxLink;
btScalar m_erp;
btScalar m_relativePositionTarget;
public:
@@ -102,7 +104,14 @@ public:
{
m_gearAuxLink = gearAuxLink;
}
virtual void setRelativePositionTarget(btScalar relPosTarget)
{
m_relativePositionTarget = relPosTarget;
}
virtual void setErp(btScalar erp)
{
m_erp = erp;
}
};
#endif //BT_MULTIBODY_GEAR_CONSTRAINT_H