bindings_SE3.py
Go to the documentation of this file.
1 import unittest
2 import pinocchio as pin
3 import numpy as np
4 from pinocchio.utils import eye,zero,rand
5 
6 ones = lambda n: np.ones([n, 1] if isinstance(n, int) else n)
7 
8 class TestSE3Bindings(unittest.TestCase):
9 
10  def test_identity(self):
11  transform = pin.SE3.Identity()
12  self.assertTrue(np.allclose(zero(3),transform.translation))
13  self.assertTrue(np.allclose(eye(3), transform.rotation))
14  self.assertTrue(np.allclose(eye(4), transform.homogeneous))
15  self.assertTrue(np.allclose(eye(6), transform.action))
16  transform.setRandom()
17  transform.setIdentity()
18  self.assertTrue(np.allclose(eye(4), transform.homogeneous))
19 
20  def test_constructor(self):
21  M = pin.SE3.Random()
22  quat = pin.Quaternion(M.rotation)
23  M_from_quat = pin.SE3(quat,M.translation)
24  self.assertTrue(M_from_quat.isApprox(M))
25 
27  transform = pin.SE3.Identity()
28  self.assertTrue(np.allclose(transform.translation, zero(3)))
29 
30  def test_get_rotation(self):
31  transform = pin.SE3.Identity()
32  self.assertTrue(np.allclose(transform.rotation, eye(3)))
33 
35  transform = pin.SE3.Identity()
36  transform.translation = ones(3)
37  self.assertFalse(np.allclose(transform.translation, zero(3)))
38  self.assertTrue(np.allclose(transform.translation, ones(3)))
39 
40  def test_set_rotation(self):
41  transform = pin.SE3.Identity()
42  transform.rotation = zero([3,3])
43  self.assertFalse(np.allclose(transform.rotation, eye(3)))
44  self.assertTrue(np.allclose(transform.rotation, zero([3,3])))
45 
46  def test_homogeneous(self):
47  amb = pin.SE3.Random()
48  H = amb.homogeneous
49  self.assertTrue(np.allclose(H[0:3,0:3], amb.rotation)) # top left 33 corner = rotation of amb
50  self.assertTrue(np.allclose(H[0:3,3], amb.translation)) # top 3 of last column = translation of amb
51  self.assertTrue(np.allclose(H[3,:], [0.,0.,0.,1.])) # last row = 0 0 0 1
52 
53  amb_from_H = pin.SE3(H)
54  self.assertTrue(amb_from_H.isApprox(amb))
55 
56  def test_action_matrix(self):
57  amb = pin.SE3.Random()
58  aXb = amb.action
59  self.assertTrue(np.allclose(aXb[:3,:3], amb.rotation)) # top left 33 corner = rotation of amb
60  self.assertTrue(np.allclose(aXb[3:,3:], amb.rotation)) # bottom right 33 corner = rotation of amb
61  tblock = pin.skew(amb.translation).dot(amb.rotation)
62  self.assertTrue(np.allclose(aXb[:3,3:], tblock)) # top right 33 corner = translation + rotation
63  self.assertTrue(np.allclose(aXb[3:,:3], zero([3,3]))) # bottom left 33 corner = 0
64 
65  def test_inverse(self):
66  amb = pin.SE3.Random()
67  aMb = amb.homogeneous
68  bma = amb.inverse()
69  self.assertTrue(np.allclose(np.linalg.inv(aMb), bma.homogeneous))
70 
72  amb = pin.SE3.Random()
73  bmc = pin.SE3.Random()
74  amc = amb*bmc
75  cma = amc.inverse()
76 
77  aMb = amb.homogeneous
78  bMc = bmc.homogeneous
79  aMc = amc.homogeneous
80  cMa = np.linalg.inv(aMc)
81 
82  self.assertTrue(np.allclose(aMb.dot(bMc), aMc))
83  self.assertTrue(np.allclose(cma.homogeneous,cMa))
84 
86  amb = pin.SE3.Random()
87  bmc = pin.SE3.Random()
88  amc = amb * bmc
89  cma = amc.inverse()
90 
91  aXb = amb.action
92  bXc = bmc.action
93  aXc = amc.action
94  cXa = np.linalg.inv(aXc)
95 
96  self.assertTrue(np.allclose(aXb.dot(bXc), aXc))
97  self.assertTrue(np.allclose(cma.action,cXa))
98 
99  def test_point_action(self):
100  amb = pin.SE3.Random()
101  aMb = amb.homogeneous
102  p_homogeneous = rand(4)
103  p_homogeneous[3] = 1
104  p = p_homogeneous[0:3].copy()
105 
106  # act
107  self.assertTrue(np.allclose(amb.act(p),(aMb.dot(p_homogeneous))[0:3]))
108 
109  # actinv
110  bMa = np.linalg.inv(aMb)
111  bma = amb.inverse()
112  self.assertTrue(np.allclose(bma.act(p), (bMa.dot(p_homogeneous))[0:3]))
113 
114  def test_member(self):
115  M = pin.SE3.Random()
116  trans = M.translation
117  M.translation[2] = 1.
118 
119  self.assertTrue(trans[2] == M.translation[2])
120 
121  def test_conversions(self):
122  def compute (m):
123  tq_vec = pin.SE3ToXYZQUAT (m)
124  tq_tup = pin.SE3ToXYZQUATtuple (m)
125  mm_vec = pin.XYZQUATToSE3 (tq_vec)
126  mm_tup = pin.XYZQUATToSE3 (tq_tup)
127  mm_lis = pin.XYZQUATToSE3 (list(tq_tup))
128  return tq_vec, tq_tup, mm_vec, mm_tup, mm_lis
129 
130  m = pin.SE3.Identity()
131  tq_vec, tq_tup, mm_vec, mm_tup, mm_lis = compute (m)
132  self.assertTrue(np.allclose(m.homogeneous, mm_tup.homogeneous))
133  self.assertTrue(np.allclose(m.homogeneous, mm_vec.homogeneous))
134  self.assertTrue(np.allclose(m.homogeneous, mm_lis.homogeneous))
135  for i in range(6):
136  self.assertTrue(tq_vec[i] == 0 and tq_tup[i] == 0)
137  self.assertTrue(tq_vec[6] == 1 and tq_tup[6] == 1)
138 
139  m = pin.SE3.Random()
140  tq_vec, tq_tup, mm_vec, mm_tup, mm_lis = compute (m)
141  self.assertTrue (len(tq_vec) == 7)
142  self.assertTrue (len(tq_tup) == 7)
143  for a,b in zip(tq_vec,tq_tup):
144  self.assertTrue (a==b)
145  self.assertTrue(np.allclose(m.homogeneous, mm_tup.homogeneous))
146  self.assertTrue (mm_vec == mm_tup)
147  self.assertTrue (mm_vec == mm_lis)
148 
149  M = pin.SE3.Random()
150  h = np.array(M)
151 
152  M_from_h = pin.SE3(h)
153  self.assertTrue(M == M_from_h)
154 
155  def test_several_init(self):
156  for _ in range(100000):
157  r = pin.SE3.Random() * pin.SE3.Random()
158  s = r.__str__()
159  self.assertTrue(s != '')
160 
161 if __name__ == '__main__':
162  unittest.main()
def test_internal_product_vs_action(self)
Definition: bindings_SE3.py:85
def test_internal_product_vs_homogeneous(self)
Definition: bindings_SE3.py:71
void copy(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &origin, DataTpl< Scalar, Options, JointCollectionTpl > &dest, KinematicLevel kinematic_level)
Copy part of the data from origin to dest. Template parameter can be used to select at which differen...
Definition: copy.hpp:52


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:28