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:
@@ -663,6 +663,7 @@ struct CalculateInverseDynamicsArgs
|
||||
double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
|
||||
double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM];
|
||||
double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM];
|
||||
int m_flags;
|
||||
};
|
||||
|
||||
struct CalculateInverseDynamicsResultArgs
|
||||
@@ -693,6 +694,8 @@ struct CalculateMassMatrixArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
|
||||
int m_dofCountQ;
|
||||
int m_flags;
|
||||
};
|
||||
|
||||
struct CalculateMassMatrixResultArgs
|
||||
|
||||
Reference in New Issue
Block a user