enable pybullet.calculateInverseDynamics for floating bodies

Using calculateInverseDynamics with zero target acceleration allows to compute the non-linear dynamics forces (coriolis/gyroscopic) and/or gravity force.
This commit is contained in:
erwincoumans
2018-11-27 08:49:56 -08:00
parent 2e30a9565b
commit 192d27743a
6 changed files with 117 additions and 31 deletions

View File

@@ -658,7 +658,8 @@ enum EnumSdfRequestInfoFlags
struct CalculateInverseDynamicsArgs
{
int m_bodyUniqueId;
int m_dofCountQ;
int m_dofCountQdot;
double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM];
double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM];
double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM];