2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
6 See LICENSE for the license information
9 Author: Frank Dellaert, Duy Nguyen Ta
19 from gtsam
import Point3, Pose3, Rot3
23 """Test selected Pose3 methods."""
26 """Test between method."""
27 T2 =
Pose3(Rot3.Rodrigues(0.3, 0.2, 0.1),
Point3(3.5, -8.2, 4.2))
28 T3 =
Pose3(Rot3.Rodrigues(-90, 0, 0),
Point3(1, 2, 3))
29 expected = T2.inverse().
compose(T3)
30 actual = T2.between(T3)
34 jacobian = np.zeros((6, 6), order=
'F')
35 jacobian_other = np.zeros((6, 6), order=
'F')
36 T2.between(T3, jacobian, jacobian_other)
43 """Test between method."""
44 pose =
Pose3(Rot3.Rodrigues(0, 0, -math.pi/2),
Point3(2, 4, 0))
45 expected =
Pose3(Rot3.Rodrigues(0, 0, math.pi/2),
Point3(4, -2, 0))
46 actual = pose.inverse()
50 jacobian = np.zeros((6, 6), order=
'F')
51 pose.inverse(jacobian)
56 """Test slerp method."""
58 pose1 =
Pose3(Rot3.Rodrigues(0, 0, -math.pi/2),
Point3(2, 4, 0))
59 actual_alpha_0 = pose0.slerp(0, pose1)
61 actual_alpha_1 = pose0.slerp(1, pose1)
63 actual_alpha_half = pose0.slerp(0.5, pose1)
64 expected_alpha_half =
Pose3(Rot3.Rodrigues(0, 0, -math.pi/4),
Point3(0.17157288, 2.41421356, 0))
68 jacobian = np.zeros((6, 6), order=
'F')
69 jacobian_other = np.zeros((6, 6), order=
'F')
70 pose0.slerp(0.5, pose1, jacobian, jacobian_other)
77 """Test transformTo method."""
78 pose =
Pose3(Rot3.Rodrigues(0, 0, -math.pi/2),
Point3(2, 4, 0))
79 actual = pose.transformTo(
Point3(3, 2, 10))
80 expected =
Point3(2, 1, 10)
85 jacobian_pose = np.zeros((3, 6), order=
'F')
86 jacobian_point = np.zeros((3, 3), order=
'F')
87 pose.transformTo(point, jacobian_pose, jacobian_point)
94 points = np.stack([
Point3(3, 2, 10),
Point3(3, 2, 10)]).T
95 actual_array = pose.transformTo(points)
96 self.assertEqual(actual_array.shape, (3, 2))
97 expected_array = np.stack([expected, expected]).T
98 np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
101 """Test transformFrom method."""
102 pose =
Pose3(Rot3.Rodrigues(0, 0, -math.pi/2),
Point3(2, 4, 0))
103 actual = pose.transformFrom(
Point3(2, 1, 10))
104 expected =
Point3(3, 2, 10)
109 jacobian_pose = np.zeros((3, 6), order=
'F')
110 jacobian_point = np.zeros((3, 3), order=
'F')
111 pose.transformFrom(point, jacobian_pose, jacobian_point)
118 points = np.stack([
Point3(2, 1, 10),
Point3(2, 1, 10)]).T
119 actual_array = pose.transformFrom(points)
120 self.assertEqual(actual_array.shape, (3, 2))
121 expected_array = np.stack([expected, expected]).T
122 np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
125 """Test range method."""
130 xl1 =
Pose3(Rot3.Ypr(0.0, 0.0, 0.0),
Point3(1, 0, 0))
131 xl2 =
Pose3(Rot3.Ypr(0.0, 1.0, 0.0),
Point3(1, 1, 0))
134 self.assertEqual(1, x1.range(point=l1))
137 self.assertEqual(math.sqrt(2.0), x1.range(point=l2))
140 self.assertEqual(1, x1.range(pose=xl1))
143 self.assertEqual(math.sqrt(2.0), x1.range(pose=xl2))
146 """Test adjoint methods."""
148 xi = np.array([1, 2, 3, 4, 5, 6])
152 T.AdjointTranspose(xi)
154 Pose3.adjoint(xi, xi)
156 expected = np.dot(Pose3.adjointMap_(xi), xi)
157 actual = Pose3.adjoint_(xi, xi)
158 np.testing.assert_array_equal(actual, expected)
161 """Test if serialization is working normally"""
162 expected =
Pose3(Rot3.Ypr(0.0, 1.0, 0.0),
Point3(1, 1, 0))
164 serialized = expected.serialize()
165 actual.deserialize(serialized)
169 """Test if Align method can align 2 squares."""
170 square = np.array([[0,0,0],[0,1,0],[1,1,0],[1,0,0]], float).T
171 sTt =
Pose3(Rot3.Rodrigues(0, 0, -math.pi),
Point3(2, 4, 0))
172 transformed = sTt.transformTo(square)
176 st_pairs.append((square[:,j], transformed[:,j]))
179 estimated_sTt = Pose3.Align(st_pairs)
183 estimated_sTt = Pose3.Align(square, transformed)
187 if __name__ ==
"__main__":