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)
19 for _
in range(self.
model.njoints):
26 null_fext = pin.StdVec_Force()
27 for _
in range(model.njoints):
28 null_fext.append(pin.Force.Zero())
30 ddq_null_fext = pin.aba(
33 self.assertApprox(ddq_null_fext, ddq)
37 null_fext_list.append(f)
39 print(
"size:", len(null_fext_list))
40 ddq_null_fext_list = pin.aba(
43 self.assertApprox(ddq_null_fext_list, ddq)
47 Minv = pin.computeMinverse(model, self.
data, self.
q)
49 data2 = model.createData()
50 M = pin.crba(model, data2, self.
q)
52 self.assertApprox(np.linalg.inv(M), Minv)
55 if __name__ ==
"__main__":