4 import pinocchio
as pin
5 from test_case
import PinocchioTestCase
as TestCase
10 R3 = pin.liegroups.R3()
11 SO3 = pin.liegroups.SO3()
13 R10 = pin.liegroups.Rn(10)
15 self.assertEqual(R3.name,
"R^3")
16 self.assertEqual(R10.name,
"R^10")
17 self.assertEqual(SO3.name,
"SO(3)")
18 self.assertEqual(R3xSO3.name, R3.name +
" x " + SO3.name)
20 self.assertEqual(R3.nq + SO3.nq, R3xSO3.nq)
21 self.assertEqual(R3.nv + SO3.nv, R3xSO3.nv)
32 pin.liegroups.R3() * pin.liegroups.SO3(),
35 v = np.random.rand(lg.nv)
37 q_int = lg.integrate(q, v)
39 _q_interpolate = lg.interpolate(q, q_int, 0.5)
41 v_diff = lg.difference(q, q_int)
42 self.assertApprox(v, v_diff)
44 J = lg.dIntegrate_dq(q, v)
46 J0 = np.random.rand(lg.nv, lg.nv)
48 J1 = lg.dIntegrate_dq(q, v, SELF, J0)
49 self.assertTrue(np.allclose(np.dot(J, J0), J1))
51 J1 = lg.dIntegrate_dq(q, v, J0, SELF)
52 self.assertTrue(np.allclose(np.dot(J0, J), J1))
54 J = lg.dIntegrate_dv(q, v)
56 J0 = np.random.rand(lg.nv, lg.nv)
58 J1 = lg.dIntegrate_dv(q, v, SELF, J0)
59 self.assertTrue(np.allclose(np.dot(J, J0), J1))
61 J1 = lg.dIntegrate_dv(q, v, J0, SELF)
62 self.assertTrue(np.allclose(np.dot(J0, J), J1))
71 pin.liegroups.R3() * pin.liegroups.SO3(),
76 for arg
in [pin.ARG0, pin.ARG1]:
77 J = lg.dDifference(q0, q1, arg)
80 J0 = np.random.rand(lg.nv, lg.nv)
82 J1 = lg.dDifference(q0, q1, arg, SELF, J0)
83 self.assertTrue(np.allclose(np.dot(J, J0), J1))
85 J1 = lg.dDifference(q0, q1, arg, J0, SELF)
86 self.assertTrue(np.allclose(np.dot(J0, J), J1))
95 pin.liegroups.R3() * pin.liegroups.SO3(),
98 v = np.random.rand(lg.nv)
100 for arg
in [pin.ARG0, pin.ARG1]:
101 Jint = lg.dIntegrate(q, v, arg)
102 J0 = np.random.rand(lg.nv, lg.nv)
103 Jout1 = lg.dIntegrateTransport(q, v, J0, arg)
104 Jout1_ref = Jint.dot(J0)
105 self.assertApprox(Jout1, Jout1_ref)
114 pin.liegroups.R3() * pin.liegroups.SO3(),
117 v = np.random.rand(lg.nv)
118 q1 = lg.integrate(q0, v)
121 tvec_at_q1 = np.random.rand(lg.nv)
122 tvec_at_q0 = lg.dIntegrateTransport(q0, v, tvec_at_q1, pin.ARG0)
126 q0_r = lg.integrate(q1, v_r)
128 self.assertApprox(q0, q0_r)
130 tvec_at_q1_r = lg.dIntegrateTransport(q1, v_r, tvec_at_q0, pin.ARG0)
132 self.assertApprox(tvec_at_q1, tvec_at_q1_r)
135 J_at_q1 = np.random.rand(lg.nv, lg.nv)
136 J_at_q0 = lg.dIntegrateTransport(q0, v, J_at_q1, pin.ARG0)
138 J_at_q1, lg.dIntegrateTransport(q1, v_r, J_at_q0, pin.ARG0)
142 if __name__ ==
"__main__":