3 from random
import random
6 import pinocchio
as pin
7 from eigenpy
import AngleAxis
8 from numpy.linalg
import inv
11 computeRpyJacobianInverse,
12 computeRpyJacobianTimeDerivative,
18 from test_case
import PinocchioTestCase
as TestCase
23 m = np.array(list(range(9)))
24 self.assertEqual(
npToTuple(m), tuple(range(9)))
25 self.assertEqual(
npToTuple(m.T), tuple(range(9)))
27 npToTuple(np.reshape(m, (3, 3))), ((0, 1, 2), (3, 4, 5), (6, 7, 8))
33 np.array([[1.0, 0.0, 0.0], [0.0, 0.0, -1.0], [0.0, 1.0, 0.0]]),
35 self.assertApprox(rotate(
"x", pi).dot(rotate(
"y", pi)), rotate(
"z", pi))
36 m = rotate(
"x", pi / 3).dot(rotate(
"y", pi / 5)).dot(rotate(
"y", pi / 7))
38 rpy = np.array(list(range(3))) * pi / 2
49 self.assertTrue(
False)
56 self.assertTrue(
False)
66 AngleAxis(y, np.array([0.0, 0.0, 1.0]))
68 .dot(AngleAxis(p, np.array([0.0, 1.0, 0.0])).matrix())
69 .dot(AngleAxis(r, np.array([1.0, 0.0, 0.0])).matrix())
72 self.assertApprox(R, Raa)
74 v = np.array([r, p, y])
78 self.assertApprox(Rv, Raa)
79 self.assertApprox(Rv, R)
84 quat = pin.Quaternion(np.random.rand(4, 1)).normalized()
85 R = quat.toRotationMatrix()
90 self.assertApprox(Rprime, R)
91 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
92 self.assertTrue(-pi / 2 <= v[1]
and v[1] <= pi / 2)
93 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
98 Rp = np.array([[0.0, 0.0, 1.0], [0.0, 1.0, 0.0], [-1.0, 0.0, 0.0]])
100 r =
random() * 2 * pi - pi
101 y =
random() * 2 * pi - pi
104 AngleAxis(y, np.array([0.0, 0.0, 1.0]))
107 .dot(AngleAxis(r, np.array([1.0, 0.0, 0.0])).matrix())
113 self.assertApprox(Rprime, R)
114 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
115 self.assertTrue(-pi / 2 <= v[1]
and v[1] <= pi / 2)
116 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
119 Rp = np.array([[0.0, 0.0, -1.0], [0.0, 1.0, 0.0], [1.0, 0.0, 0.0]])
121 r =
random() * 2 * pi - pi
122 y =
random() * 2 * pi - pi
125 AngleAxis(y, np.array([0.0, 0.0, 1.0]))
128 .dot(AngleAxis(r, np.array([1.0, 0.0, 0.0])).matrix())
134 self.assertApprox(Rprime, R)
135 self.assertTrue(-pi <= v[0]
and v[0] <= pi)
136 self.assertTrue(-pi / 2 <= v[1]
and v[1] <= pi / 2)
137 self.assertTrue(-pi <= v[2]
and v[2] <= pi)
143 self.assertTrue((j0 == np.eye(3)).all())
145 self.assertTrue((jL == np.eye(3)).all())
147 self.assertTrue((jW == np.eye(3)).all())
149 self.assertTrue((jA == np.eye(3)).all())
152 r =
random() * 2 * pi - pi
153 p =
random() * pi - pi / 2
154 y =
random() * 2 * pi - pi
155 rpy = np.array([r, p, y])
161 self.assertTrue((j0 == jL).all())
162 self.assertTrue((jW == jA).all())
163 self.assertApprox(jW, R.dot(jL))
166 rpydot = np.random.rand(3)
173 Rdot = dRdr * rpydot[0] + dRdp * rpydot[1] + dRdy * rpydot[2]
175 omegaL = jL.dot(rpydot)
176 self.assertTrue(np.allclose(Rdot, R.dot(pin.skew(omegaL)), atol=tol))
178 omegaW = jW.dot(rpydot)
179 self.assertTrue(np.allclose(Rdot, pin.skew(omegaW).dot(R), atol=tol))
183 r =
random() * 2 * pi - pi
184 p =
random() * pi - pi / 2
186 y =
random() * 2 * pi - pi
187 rpy = np.array([r, p, y])
191 self.assertApprox(j0inv, inv(j0))
195 self.assertApprox(jLinv, inv(jL))
199 self.assertApprox(jWinv, inv(jW))
203 self.assertApprox(jAinv, inv(jA))
207 r =
random() * 2 * pi - pi
208 p =
random() * pi - pi / 2
209 y =
random() * 2 * pi - pi
210 rpy = np.array([r, p, y])
213 self.assertTrue((dj0 == np.zeros((3, 3))).all())
215 self.assertTrue((djL == np.zeros((3, 3))).all())
217 self.assertTrue((djW == np.zeros((3, 3))).all())
219 self.assertTrue((djA == np.zeros((3, 3))).all())
222 rpydot = np.random.rand(3)
227 self.assertTrue((dj0 == djL).all())
228 self.assertTrue((djW == djA).all())
233 omegaL = jL.dot(rpydot)
234 omegaW = jW.dot(rpydot)
235 self.assertApprox(omegaW, R.dot(omegaL))
236 self.assertApprox(djW, pin.skew(omegaW).dot(R).dot(jL) + R.dot(djL))
237 self.assertApprox(djW, R.dot(pin.skew(omegaL)).dot(jL) + R.dot(djL))
240 if __name__ ==
"__main__":