bindings_dynamics.py
Go to the documentation of this file.
1 import unittest
2 from test_case import PinocchioTestCase as TestCase
3 import pinocchio as pin
4 from pinocchio.utils import rand, zero
5 import numpy as np
6 
7 import warnings
8 
9 # common quantities for all tests.
10 # They correspond to the default values of the arguments, and they need to stay this way
11 r_coeff = 0.0
12 inv_damping = 0.0
13 
14 
15 class TestDynamicsBindings(TestCase):
16  def setUp(self):
17  self.model = pin.buildSampleModelHumanoidRandom()
18  self.data = self.model.createData()
19 
20  qmax = np.full((self.model.nq, 1), np.pi)
21  self.q = pin.randomConfiguration(self.model, -qmax, qmax)
22  self.v = rand(self.model.nv)
23  self.tau = rand(self.model.nv)
24 
25  self.v0 = zero(self.model.nv)
26  self.tau0 = zero(self.model.nv)
27  self.tolerance = 1e-9
28 
29  # we compute J on a different self.data
30  self.J = pin.computeJointJacobian(
31  self.model,
32  self.model.createData(),
33  self.q,
34  self.model.getJointId("lleg6_joint"),
35  )
36  self.gamma = zero(6)
37 
39  data_no_q = self.model.createData()
40 
41  self.model.gravity = pin.Motion.Zero()
42  ddq = pin.forwardDynamics(
43  self.model, self.data, self.q, self.v0, self.tau0, self.J, self.gamma
44  )
45  self.assertLess(np.linalg.norm(ddq), self.tolerance)
46 
47  KKT_inverse = pin.getKKTContactDynamicMatrixInverse(
48  self.model, self.data, self.J
49  )
50  M = pin.crba(self.model, self.model.createData(), self.q)
51 
52  self.assertApprox(
53  M, np.linalg.inv(KKT_inverse)[: self.model.nv, : self.model.nv]
54  )
55 
56  pin.computeAllTerms(self.model, data_no_q, self.q, self.v0)
57  ddq_no_q = pin.forwardDynamics(
58  self.model, data_no_q, self.tau0, self.J, self.gamma
59  )
60  self.assertLess(np.linalg.norm(ddq_no_q), self.tolerance)
61 
62  self.assertApprox(ddq, ddq_no_q)
63 
65  model = self.model
66  data = model.createData()
67  data_ref = model.createData()
68 
69  q = self.q
70  v = self.v
71  tau = self.tau0
72  J = self.J
73  gamma = self.gamma
74 
75  pin.forwardDynamics(model, data_ref, q, v, tau, J, gamma)
76  KKT_inverse_ref = pin.getKKTContactDynamicMatrixInverse(model, data_ref, J)
77 
78  KKT_inverse = pin.computeKKTContactDynamicMatrixInverse(model, data, q, J)
79  KKT_inverse2 = pin.computeKKTContactDynamicMatrixInverse(model, data, q, J, 0.0)
80  self.assertApprox(KKT_inverse, KKT_inverse_ref)
81  self.assertApprox(KKT_inverse2, KKT_inverse_ref)
82 
84  data_no_q = self.model.createData()
85 
86  self.model.gravity = pin.Motion.Zero()
87  ddq = pin.forwardDynamics(
88  self.model,
89  self.data,
90  self.q,
91  self.v0,
92  self.tau0,
93  self.J,
94  self.gamma,
95  r_coeff,
96  )
97  self.assertLess(np.linalg.norm(ddq), self.tolerance)
98 
99  pin.computeAllTerms(self.model, data_no_q, self.q, self.v0)
100  ddq_no_q = pin.forwardDynamics(
101  self.model, data_no_q, self.tau0, self.J, self.gamma, r_coeff
102  )
103  self.assertLess(np.linalg.norm(ddq_no_q), self.tolerance)
104 
105  self.assertApprox(ddq, ddq_no_q)
106 
108  data7 = self.data
109  data8 = self.model.createData()
110  data9_deprecated = self.model.createData()
111  ddq7 = pin.forwardDynamics(
112  self.model, data7, self.q, self.v, self.tau, self.J, self.gamma
113  )
114  ddq8 = pin.forwardDynamics(
115  self.model, data8, self.q, self.v, self.tau, self.J, self.gamma, r_coeff
116  )
117 
118  self.assertTrue((ddq7 == ddq8).all())
119 
121  data5 = self.data
122  data6 = self.model.createData()
123  data9_deprecated = self.model.createData()
124  pin.computeAllTerms(self.model, data5, self.q, self.v0)
125  pin.computeAllTerms(self.model, data6, self.q, self.v0)
126  pin.computeAllTerms(self.model, data9_deprecated, self.q, self.v0)
127  ddq5 = pin.forwardDynamics(self.model, data5, self.tau, self.J, self.gamma)
128  ddq6 = pin.forwardDynamics(
129  self.model, data6, self.tau, self.J, self.gamma, r_coeff
130  )
131  self.assertTrue((ddq5 == ddq6).all())
132 
134  data_no_q = self.model.createData()
135 
136  vnext = pin.impulseDynamics(self.model, self.data, self.q, self.v0, self.J)
137  self.assertLess(np.linalg.norm(vnext), self.tolerance)
138 
139  pin.crba(self.model, data_no_q, self.q)
140  vnext_no_q = pin.impulseDynamics(self.model, data_no_q, self.v0, self.J)
141  self.assertLess(np.linalg.norm(vnext_no_q), self.tolerance)
142 
143  self.assertApprox(vnext, vnext_no_q)
144 
146  data_no_q = self.model.createData()
147 
148  vnext = pin.impulseDynamics(
149  self.model, self.data, self.q, self.v0, self.J, r_coeff
150  )
151  self.assertLess(np.linalg.norm(vnext), self.tolerance)
152 
153  pin.crba(self.model, data_no_q, self.q)
154  vnext_no_q = pin.impulseDynamics(
155  self.model, data_no_q, self.v0, self.J, r_coeff
156  )
157  self.assertLess(np.linalg.norm(vnext_no_q), self.tolerance)
158 
159  self.assertApprox(vnext, vnext_no_q)
160 
162  data_no_q = self.model.createData()
163 
164  vnext = pin.impulseDynamics(
165  self.model, self.data, self.q, self.v0, self.J, r_coeff, inv_damping
166  )
167  self.assertLess(np.linalg.norm(vnext), self.tolerance)
168 
169  pin.crba(self.model, data_no_q, self.q)
170  vnext_no_q = pin.impulseDynamics(
171  self.model, data_no_q, self.v0, self.J, r_coeff, inv_damping
172  )
173  self.assertLess(np.linalg.norm(vnext_no_q), self.tolerance)
174 
175  self.assertApprox(vnext, vnext_no_q)
176 
178  data5 = self.data
179  data6 = self.model.createData()
180  data7 = self.model.createData()
181  data7_deprecated = self.model.createData()
182  vnext5 = pin.impulseDynamics(self.model, data5, self.q, self.v, self.J)
183  vnext6 = pin.impulseDynamics(self.model, data6, self.q, self.v, self.J, r_coeff)
184  vnext7 = pin.impulseDynamics(
185  self.model, data7, self.q, self.v, self.J, r_coeff, inv_damping
186  )
187  self.assertTrue((vnext5 == vnext6).all())
188  self.assertTrue((vnext5 == vnext7).all())
189  self.assertTrue((vnext6 == vnext7).all())
190 
192  data4 = self.data
193  data5 = self.model.createData()
194  data6 = self.model.createData()
195  data7_deprecated = self.model.createData()
196  pin.crba(self.model, data4, self.q)
197  pin.crba(self.model, data5, self.q)
198  pin.crba(self.model, data6, self.q)
199  pin.crba(self.model, data7_deprecated, self.q)
200  vnext4 = pin.impulseDynamics(self.model, data4, self.v, self.J)
201  vnext5 = pin.impulseDynamics(self.model, data5, self.v, self.J, r_coeff)
202  vnext6 = pin.impulseDynamics(
203  self.model, data6, self.v, self.J, r_coeff, inv_damping
204  )
205 
206  self.assertTrue((vnext4 == vnext5).all())
207  self.assertTrue((vnext4 == vnext6).all())
208  self.assertTrue((vnext5 == vnext6).all())
209 
210 
211 if __name__ == "__main__":
212  unittest.main()
bindings_dynamics.TestDynamicsBindings.v0
v0
Definition: bindings_dynamics.py:25
bindings_dynamics.TestDynamicsBindings.gamma
gamma
Definition: bindings_dynamics.py:36
bindings_dynamics.TestDynamicsBindings.test_impulseDynamics_default
def test_impulseDynamics_default(self)
Definition: bindings_dynamics.py:133
bindings_dynamics.TestDynamicsBindings.data
data
Definition: bindings_dynamics.py:18
bindings_dynamics.TestDynamicsBindings.setUp
def setUp(self)
Definition: bindings_dynamics.py:16
bindings_dynamics.TestDynamicsBindings.test_impulseDynamics_r
def test_impulseDynamics_r(self)
Definition: bindings_dynamics.py:145
bindings_dynamics.TestDynamicsBindings.test_forwardDynamics_default
def test_forwardDynamics_default(self)
Definition: bindings_dynamics.py:38
bindings_dynamics.TestDynamicsBindings.test_impulseDynamics_rd
def test_impulseDynamics_rd(self)
Definition: bindings_dynamics.py:161
bindings_dynamics.TestDynamicsBindings.test_computeKKTMatrix
def test_computeKKTMatrix(self)
Definition: bindings_dynamics.py:64
bindings_dynamics.TestDynamicsBindings.tolerance
tolerance
Definition: bindings_dynamics.py:27
bindings_dynamics.TestDynamicsBindings.q
q
Definition: bindings_dynamics.py:21
pinocchio.utils
Definition: bindings/python/pinocchio/utils.py:1
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:248
bindings_dynamics.TestDynamicsBindings.tau0
tau0
Definition: bindings_dynamics.py:26
bindings_dynamics.TestDynamicsBindings.test_forwardDynamics_q
def test_forwardDynamics_q(self)
Definition: bindings_dynamics.py:107
bindings_dynamics.TestDynamicsBindings.J
J
Definition: bindings_dynamics.py:30
bindings_dynamics.TestDynamicsBindings
Definition: bindings_dynamics.py:15
bindings_dynamics.TestDynamicsBindings.model
model
Definition: bindings_dynamics.py:17
bindings_dynamics.TestDynamicsBindings.test_forwardDynamics_rcoeff
def test_forwardDynamics_rcoeff(self)
Definition: bindings_dynamics.py:83
bindings_dynamics.TestDynamicsBindings.tau
tau
Definition: bindings_dynamics.py:23
pinocchio.utils.rand
def rand(n)
Definition: bindings/python/pinocchio/utils.py:42
bindings_dynamics.TestDynamicsBindings.test_forwardDynamics_no_q
def test_forwardDynamics_no_q(self)
Definition: bindings_dynamics.py:120
bindings_dynamics.TestDynamicsBindings.v
v
Definition: bindings_dynamics.py:22
pinocchio.utils.zero
def zero(n)
Definition: bindings/python/pinocchio/utils.py:38
bindings_dynamics.TestDynamicsBindings.test_impulseDynamics_q
def test_impulseDynamics_q(self)
Definition: bindings_dynamics.py:177
bindings_dynamics.TestDynamicsBindings.test_impulseDynamics_no_q
def test_impulseDynamics_no_q(self)
Definition: bindings_dynamics.py:191


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:31