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:
@@ -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];
|
||||
|
||||
Reference in New Issue
Block a user