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 res = pin.computeCentroidalDynamicsDerivatives(
23 self.assertTrue(len(res) == 4)
26 pin.computeCentroidalMomentumTimeVariation(
27 self.
model, data2, self.
q, self.
v, self.
a
30 self.assertApprox(self.
data.hg, data2.hg)
31 self.assertApprox(self.
data.dhg, data2.dhg)
34 pin.computeRNEADerivatives(self.
model, data3, self.
q, self.
v, self.
a)
35 res2 = pin.getCentroidalDynamicsDerivatives(self.
model, data3)
38 self.assertApprox(res[k], res2[k])
41 if __name__ ==
"__main__":