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


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:34