bindings_main_algo.py
Go to the documentation of this file.
1 import os
2 import sys
3 import unittest
4 
5 sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
6 import casadi
7 import numpy as np
8 import pinocchio as pin
9 from casadi import SX
10 from pinocchio import casadi as cpin
11 from test_case import PinocchioTestCase as TestCase
12 
13 
14 class TestMainAlgos(TestCase):
15  def setUp(self):
16  self.model = pin.buildSampleModelHumanoidRandom()
17  self.data = self.model.createData()
18 
19  self.cmodel = cpin.Model(self.model)
20  self.cdata = self.cmodel.createData()
21 
22  qmax = np.full((self.model.nq, 1), np.pi)
23  self.q = pin.randomConfiguration(self.model, -qmax, qmax)
24  self.v = np.random.rand(self.model.nv)
25  self.a = np.random.rand(self.model.nv)
26  self.tau = np.random.rand(self.model.nv)
27 
28  self.cq = SX.sym("q", self.cmodel.nq, 1)
29  self.cv = SX.sym("v", self.cmodel.nv, 1)
30  self.ca = SX.sym("a", self.cmodel.nv, 1)
31  self.ctau = SX.sym("tau", self.cmodel.nv, 1)
32 
33  self.fext = []
34  self.cfext = []
35  for i in range(self.model.njoints):
36  self.fext.append(pin.Force.Random())
37  fname = "f" + str(i)
38  self.cfext.append(cpin.Force(SX.sym(fname, 6, 1)))
39 
40  self.fext[0].setZero()
41 
42  def test_crba(self):
43  model = self.model
44  data = self.data
45 
46  cmodel = self.cmodel
47  cdata = self.cdata
48 
49  cM = cpin.crba(cmodel, cdata, self.cq)
50  f_crba = casadi.Function("crba", [self.cq], [cM])
51 
52  arg_crba = [list(self.q)]
53  M = f_crba.call(arg_crba)[0].full()
54 
55  M_ref = pin.crba(model, data, self.q)
56 
57  self.assertApprox(M, M_ref)
58 
59  def test_rnea(self):
60  model = self.model
61  data = self.data
62 
63  cmodel = self.cmodel
64  cdata = self.cdata
65 
66  ctau = cpin.rnea(cmodel, cdata, self.cq, self.cv, self.ca)
67  f_rnea = casadi.Function("rnea", [self.cq, self.cv, self.ca], [ctau])
68 
69  arg_rnea = [list(self.q), list(self.v), list(self.a)]
70  tau = f_rnea.call(arg_rnea)[0].full()
71 
72  tau_ref = pin.rnea(model, data, self.q, self.v, self.a)
73 
74  self.assertApprox(tau, tau_ref)
75 
76  ctau_fext = cpin.rnea(cmodel, cdata, self.cq, self.cv, self.ca, self.cfext)
77  carg_in = [self.cq, self.cv, self.ca]
78  for f in self.cfext:
79  carg_in += [f.vector]
80  f_rnea_fext = casadi.Function("rnea_fext", carg_in, [ctau_fext])
81 
82  arg_rnea_fext = arg_rnea
83  for f in self.fext:
84  arg_rnea_fext += [f.vector]
85  tau_fext = f_rnea_fext.call(arg_rnea_fext)[0].full()
86 
87  tau_fext_ref = pin.rnea(model, data, self.q, self.v, self.a, self.fext)
88 
89  self.assertApprox(tau_fext, tau_fext_ref)
90 
91  def test_aba(self):
92  model = self.model
93  data = self.data
94 
95  cmodel = self.cmodel
96  cdata = self.cdata
97 
98  cddq = cpin.aba(cmodel, cdata, self.cq, self.cv, self.ctau)
99  f_aba = casadi.Function("aba", [self.cq, self.cv, self.ctau], [cddq])
100 
101  arg_aba = [list(self.q), list(self.v), list(self.tau)]
102  a = f_aba.call(arg_aba)[0].full()
103 
104  a_ref = pin.aba(model, data, self.q, self.v, self.tau)
105 
106  self.assertApprox(a, a_ref)
107 
108  cddq_fext = cpin.aba(cmodel, cdata, self.cq, self.cv, self.ctau, self.cfext)
109  carg_in = [self.cq, self.cv, self.ctau]
110  for f in self.cfext:
111  carg_in += [f.vector]
112  f_aba_fext = casadi.Function("aba_fext", carg_in, [cddq_fext])
113 
114  arg_aba_fext = arg_aba
115  for f in self.fext:
116  arg_aba_fext += [f.vector]
117  a_fext = f_aba_fext.call(arg_aba_fext)[0].full()
118 
119  a_fext_ref = pin.aba(model, data, self.q, self.v, self.tau, self.fext)
120 
121  self.assertApprox(a_fext, a_fext_ref)
122 
124  model = self.model
125  Minv = pin.computeMinverse(model, self.data, self.q)
126 
127  data2 = model.createData()
128  M = pin.crba(model, data2, self.q)
129 
130  self.assertApprox(np.linalg.inv(M), Minv)
131 
132 
133 if __name__ == "__main__":
134  unittest.main()
bindings_main_algo.TestMainAlgos.cq
cq
Definition: bindings_main_algo.py:28
bindings_main_algo.TestMainAlgos.test_rnea
def test_rnea(self)
Definition: bindings_main_algo.py:59
bindings_main_algo.TestMainAlgos.test_crba
def test_crba(self)
Definition: bindings_main_algo.py:42
bindings_main_algo.TestMainAlgos.a
a
Definition: bindings_main_algo.py:25
bindings_main_algo.TestMainAlgos.ca
ca
Definition: bindings_main_algo.py:30
bindings_main_algo.TestMainAlgos.ctau
ctau
Definition: bindings_main_algo.py:31
bindings_main_algo.TestMainAlgos.cmodel
cmodel
Definition: bindings_main_algo.py:19
bindings_main_algo.TestMainAlgos.q
q
Definition: bindings_main_algo.py:23
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:248
bindings_main_algo.TestMainAlgos.test_aba
def test_aba(self)
Definition: bindings_main_algo.py:91
bindings_main_algo.TestMainAlgos.fext
fext
Definition: bindings_main_algo.py:33
bindings_main_algo.TestMainAlgos.cfext
cfext
Definition: bindings_main_algo.py:34
bindings_main_algo.TestMainAlgos.tau
tau
Definition: bindings_main_algo.py:26
bindings_main_algo.TestMainAlgos.cdata
cdata
Definition: bindings_main_algo.py:20
bindings_main_algo.TestMainAlgos.setUp
def setUp(self)
Definition: bindings_main_algo.py:15
boost::fusion::append
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:32
bindings_main_algo.TestMainAlgos.model
model
Definition: bindings_main_algo.py:16
bindings_main_algo.TestMainAlgos.cv
cv
Definition: bindings_main_algo.py:29
bindings_main_algo.TestMainAlgos.v
v
Definition: bindings_main_algo.py:24
bindings_main_algo.TestMainAlgos
Definition: bindings_main_algo.py:14
bindings_main_algo.TestMainAlgos.data
data
Definition: bindings_main_algo.py:17
bindings_main_algo.TestMainAlgos.test_computeMinverse
def test_computeMinverse(self)
Definition: bindings_main_algo.py:123


pinocchio
Author(s):
autogenerated on Sat Sep 28 2024 02:41:15