4 import pinocchio
as pin
5 from test_case
import PinocchioTestCase
as TestCase
10 self.
model = pin.buildSampleModelHumanoidRandom()
13 qmax = np.full((self.
model.nq, 1), np.pi)
14 self.
q = pin.randomConfiguration(self.
model, -qmax, qmax)
15 self.
v = np.random.rand(self.
model.nv)
16 self.
a = np.random.rand(self.
model.nv)
19 for _
in range(self.
model.njoints):
24 tau = pin.rnea(self.
model, self.
data, self.
q, self.
v, self.
a)
26 null_fext = pin.StdVec_Force()
27 for k
in range(model.njoints):
28 null_fext.append(pin.Force.Zero())
30 tau_null_fext = pin.rnea(
33 self.assertApprox(tau_null_fext, tau)
37 null_fext_list.append(f)
39 print(
"size:", len(null_fext_list))
40 tau_null_fext_list = pin.rnea(
41 self.
model, self.
data, self.
q, self.
v, self.
a, null_fext_list
43 self.assertApprox(tau_null_fext_list, tau)
48 tau = pin.nonLinearEffects(model, self.
data, self.
q, self.
v)
50 data2 = model.createData()
51 tau_ref = pin.rnea(model, data2, self.
q, self.
v, self.
a * 0)
53 self.assertApprox(tau, tau_ref)
58 tau = pin.computeGeneralizedGravity(model, self.
data, self.
q)
60 data2 = model.createData()
61 tau_ref = pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0)
63 self.assertApprox(tau, tau_ref)
68 tau = pin.computeStaticTorque(model, self.
data, self.
q, self.
fext)
70 data2 = model.createData()
71 tau_ref = pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0, self.
fext)
73 self.assertApprox(tau, tau_ref)
78 C = pin.computeCoriolisMatrix(model, self.
data, self.
q, self.
v)
80 data2 = model.createData()
81 tau_coriolis_ref = pin.rnea(
82 model, data2, self.
q, self.
v, self.
a * 0
83 ) - pin.rnea(model, data2, self.
q, self.
v * 0, self.
a * 0)
85 self.assertApprox(tau_coriolis_ref, C.dot(self.
v))
88 if __name__ ==
"__main__":