2 from test_case
import PinocchioTestCase
as TestCase
4 import pinocchio
as pin
10 self.
model = pin.buildSampleModelHumanoidRandom()
11 self.
data = self.model.createData()
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))
20 res = pin.computeCentroidalDynamicsDerivatives(self.
model,self.
data,self.
q,self.
v,self.
a)
22 self.assertTrue(len(res) == 4)
24 data2 = self.model.createData()
25 pin.computeCentroidalMomentumTimeVariation(self.
model,data2,self.
q,self.
v,self.
a)
27 self.assertApprox(self.data.hg,data2.hg)
28 self.assertApprox(self.data.dhg,data2.dhg)
30 data3 = self.model.createData()
31 pin.computeRNEADerivatives(self.
model,data3,self.
q,self.
v,self.
a)
32 res2 = pin.getCentroidalDynamicsDerivatives(self.
model,data3)
35 self.assertApprox(res[k],res2[k])
37 if __name__ ==
'__main__':
def test_centroidal_derivatives(self)