bindings_forward_dynamics_derivatives.py
Go to the documentation of this file.
1 import unittest
2 from test_case import PinocchioTestCase as TestCase
3 
4 import pinocchio as pin
5 import numpy as np
6 
7 class TestDeriavtives(TestCase):
8 
9  def setUp(self):
10  self.model = pin.buildSampleModelHumanoidRandom()
11  self.data = self.model.createData()
12 
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.tau = np.random.rand((self.model.nv))
17 
18  self.fext = []
19  for _ in range(self.model.njoints):
20  self.fext.append(pin.Force.Random())
21 
23  res = pin.computeABADerivatives(self.model,self.data,self.q,self.v,self.tau)
24 
25  self.assertTrue(len(res) == 3)
26 
27  data2 = self.model.createData()
28  pin.aba(self.model,data2,self.q,self.v,self.tau)
29 
30  self.assertApprox(self.data.ddq,data2.ddq)
31 
32  # With external forces
33  res = pin.computeABADerivatives(self.model,self.data,self.q,self.v,self.tau,self.fext)
34 
35  self.assertTrue(len(res) == 3)
36 
37  pin.aba(self.model,data2,self.q,self.v,self.tau,self.fext)
38 
39  self.assertApprox(self.data.ddq,data2.ddq)
40 
41 if __name__ == '__main__':
42  unittest.main()


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02