-
I have a question that probably comes down to some frame convention that I'm missing.
And I have a minimal test script calling RNEA here:
So, the first two show the gravity force in Z. The third one also shows a negative force in Y, which looks to me to be like a cross product term: |
Beta Was this translation helpful? Give feedback.
Replies: 3 comments
-
I have a modified version of the same test where I add 1 revolute dof:
And modified script to change the floating body angular velocity to be a velocity in the revolute joint instead:
In my mind, this is basically the same model as the point mass above, except that I added a massless link in between the floating base and the point mass. But now, that cross term has gone away. |
Beta Was this translation helpful? Give feedback.
-
To shortly answer your question, the |
Beta Was this translation helpful? Give feedback.
-
Also, don't forget to use import pinocchio as pin
from pinocchio.utils import *
import numpy as np
model = pin.buildModelFromUrdf("point_mass.urdf", pin.JointModelFreeFlyer())
data = pin.Data(model)
q = pin.neutral(model)
qdd = np.array([0,0,0,0,0,0])
qd = np.array([0,0,0,0,0,0])
pin.computeAllTerms(model, data, q, qd)
print(pin.rnea(model, data, q, qd, qdd))
# prints [0. 0. 9.81 0. 0. 0. ]
qd = np.array([0,0,1,0,0,0])
pin.computeAllTerms(model, data, q, qd)
print(pin.rnea(model, data, q, qd, qdd))
# prints [0. 0. 9.81 0. 0. 0. ]
qd = np.array([0,0,1,1,0,0])
pin.computeAllTerms(model, data, q, qd)
print(pin.rnea(model, data, q, qd, qdd))
# prints [ 0. -1. 9.81 0. 0. 0. ] |
Beta Was this translation helpful? Give feedback.
To shortly answer your question, the
[0, -1, 0]
is coming from the Coriolis/Centrifugal effects that you can compute via:pin.computeCoriolisMatrix(model,data,q,qd) @ qd