test_Pose3.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 Pose3 unit tests.
9 Author: Frank Dellaert, Duy Nguyen Ta
10 """
11 # pylint: disable=no-name-in-module
12 import math
13 import unittest
14 
15 import numpy as np
16 from gtsam.utils.test_case import GtsamTestCase
17 
18 import gtsam
19 from gtsam import Point3, Pose3, Rot3
20 from gtsam.utils.numerical_derivative import numericalDerivative11, numericalDerivative21, numericalDerivative22
21 
23  """Test selected Pose3 methods."""
24 
25  def test_between(self):
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)
31  self.gtsamAssertEquals(actual, expected, 1e-6)
32 
33  #test jacobians
34  jacobian = np.zeros((6, 6), order='F')
35  jacobian_other = np.zeros((6, 6), order='F')
36  T2.between(T3, jacobian, jacobian_other)
37  jacobian_numerical = numericalDerivative21(Pose3.between, T2, T3)
38  jacobian_numerical_other = numericalDerivative22(Pose3.between, T2, T3)
39  self.gtsamAssertEquals(jacobian, jacobian_numerical)
40  self.gtsamAssertEquals(jacobian_other, jacobian_numerical_other)
41 
42  def test_inverse(self):
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()
47  self.gtsamAssertEquals(actual, expected, 1e-6)
48 
49  #test jacobians
50  jacobian = np.zeros((6, 6), order='F')
51  pose.inverse(jacobian)
52  jacobian_numerical = numericalDerivative11(Pose3.inverse, pose)
53  self.gtsamAssertEquals(jacobian, jacobian_numerical)
54 
55  def test_slerp(self):
56  """Test slerp method."""
57  pose0 = gtsam.Pose3()
58  pose1 = Pose3(Rot3.Rodrigues(0, 0, -math.pi/2), Point3(2, 4, 0))
59  actual_alpha_0 = pose0.slerp(0, pose1)
60  self.gtsamAssertEquals(actual_alpha_0, pose0)
61  actual_alpha_1 = pose0.slerp(1, pose1)
62  self.gtsamAssertEquals(actual_alpha_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))
65  self.gtsamAssertEquals(actual_alpha_half, expected_alpha_half, tol=1e-6)
66 
67  # test jacobians
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)
71  jacobian_numerical = numericalDerivative11(lambda x: x.slerp(0.5, pose1), pose0)
72  jacobian_numerical_other = numericalDerivative11(lambda x: pose0.slerp(0.5, x), pose1)
73  self.gtsamAssertEquals(jacobian, jacobian_numerical)
74  self.gtsamAssertEquals(jacobian_other, jacobian_numerical_other)
75 
76  def test_transformTo(self):
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)
81  self.gtsamAssertEquals(actual, expected, 1e-6)
82 
83  #test jacobians
84  point = Point3(3, 2, 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)
88  jacobian_numerical_pose = numericalDerivative21(Pose3.transformTo, pose, point)
89  jacobian_numerical_point = numericalDerivative22(Pose3.transformTo, pose, point)
90  self.gtsamAssertEquals(jacobian_pose, jacobian_numerical_pose)
91  self.gtsamAssertEquals(jacobian_point, jacobian_numerical_point)
92 
93  # multi-point version
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)
99 
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)
105  self.gtsamAssertEquals(actual, expected, 1e-6)
106 
107  #test jacobians
108  point = 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)
112  jacobian_numerical_pose = numericalDerivative21(Pose3.transformFrom, pose, point)
113  jacobian_numerical_point = numericalDerivative22(Pose3.transformFrom, pose, point)
114  self.gtsamAssertEquals(jacobian_pose, jacobian_numerical_pose)
115  self.gtsamAssertEquals(jacobian_point, jacobian_numerical_point)
116 
117  # multi-point version
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)
123 
124  def test_range(self):
125  """Test range method."""
126  l1 = Point3(1, 0, 0)
127  l2 = Point3(1, 1, 0)
128  x1 = Pose3()
129 
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))
132 
133  # establish range is indeed zero
134  self.assertEqual(1, x1.range(point=l1))
135 
136  # establish range is indeed sqrt2
137  self.assertEqual(math.sqrt(2.0), x1.range(point=l2))
138 
139  # establish range is indeed zero
140  self.assertEqual(1, x1.range(pose=xl1))
141 
142  # establish range is indeed sqrt2
143  self.assertEqual(math.sqrt(2.0), x1.range(pose=xl2))
144 
145  def test_adjoint(self):
146  """Test adjoint methods."""
147  T = Pose3()
148  xi = np.array([1, 2, 3, 4, 5, 6])
149  # test calling functions
150  T.AdjointMap()
151  T.Adjoint(xi)
152  T.AdjointTranspose(xi)
153  Pose3.adjointMap(xi)
154  Pose3.adjoint(xi, xi)
155  # test correctness of adjoint(x, y)
156  expected = np.dot(Pose3.adjointMap_(xi), xi)
157  actual = Pose3.adjoint_(xi, xi)
158  np.testing.assert_array_equal(actual, expected)
159 
161  """Test if serialization is working normally"""
162  expected = Pose3(Rot3.Ypr(0.0, 1.0, 0.0), Point3(1, 1, 0))
163  actual = Pose3()
164  serialized = expected.serialize()
165  actual.deserialize(serialized)
166  self.gtsamAssertEquals(expected, actual, 1e-10)
167 
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)
173 
174  st_pairs = []
175  for j in range(4):
176  st_pairs.append((square[:,j], transformed[:,j]))
177 
178  # Recover the transformation sTt
179  estimated_sTt = Pose3.Align(st_pairs)
180  self.gtsamAssertEquals(estimated_sTt, sTt, 1e-10)
181 
182  # Matrix version
183  estimated_sTt = Pose3.Align(square, transformed)
184  self.gtsamAssertEquals(estimated_sTt, sTt, 1e-10)
185 
186 
187 if __name__ == "__main__":
188  unittest.main()
test_Pose3.TestPose3.test_align_squares
def test_align_squares(self)
Definition: test_Pose3.py:168
gtsam::numericalDerivative11
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition: numericalDerivative.h:110
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::utils.test_case.GtsamTestCase.gtsamAssertEquals
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:19
test_Pose3.TestPose3.test_inverse
def test_inverse(self)
Definition: test_Pose3.py:42
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
test_Pose3.TestPose3.test_adjoint
def test_adjoint(self)
Definition: test_Pose3.py:145
gtsam::Pose3
Definition: Pose3.h:37
test_Pose3.TestPose3.test_serialization
def test_serialization(self)
Definition: test_Pose3.py:160
gtsam::utils.test_case
Definition: test_case.py:1
test_Pose3.TestPose3.test_between
def test_between(self)
Definition: test_Pose3.py:25
gtsam::utils.numerical_derivative
Definition: numerical_derivative.py:1
test_Pose3.TestPose3.test_transformTo
def test_transformTo(self)
Definition: test_Pose3.py:76
test_Pose3.TestPose3.test_range
def test_range(self)
Definition: test_Pose3.py:124
gtsam::testing::compose
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
test_Pose3.TestPose3.test_slerp
def test_slerp(self)
Definition: test_Pose3.py:55
gtsam::utils.test_case.GtsamTestCase
Definition: test_case.py:16
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
test_Pose3.TestPose3.test_transformFrom
def test_transformFrom(self)
Definition: test_Pose3.py:100
test_Pose3.TestPose3
Definition: test_Pose3.py:22


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:15:58