test_Pose2.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 Pose2 unit tests.
9 Author: Frank Dellaert & Duy Nguyen Ta & John Lambert
10 """
11 import math
12 import unittest
13 
14 import numpy as np
15 from gtsam.utils.test_case import GtsamTestCase
16 
17 from gtsam import Point2, Point2Pairs, Pose2
18 
19 
21  """Test selected Pose2 methods."""
22 
23  def test_adjoint(self) -> None:
24  """Test adjoint method."""
25  xi = np.array([1, 2, 3])
26  expected = np.dot(Pose2.adjointMap_(xi), xi)
27  actual = Pose2.adjoint_(xi, xi)
28  np.testing.assert_array_equal(actual, expected)
29 
30  def test_transformTo(self):
31  """Test transformTo method."""
32  pose = Pose2(2, 4, -math.pi / 2)
33  actual = pose.transformTo(Point2(3, 2))
34  expected = Point2(2, 1)
35  self.gtsamAssertEquals(actual, expected, 1e-6)
36 
37  # multi-point version
38  points = np.stack([Point2(3, 2), Point2(3, 2)]).T
39  actual_array = pose.transformTo(points)
40  self.assertEqual(actual_array.shape, (2, 2))
41  expected_array = np.stack([expected, expected]).T
42  np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
43 
44  def test_transformFrom(self):
45  """Test transformFrom method."""
46  pose = Pose2(2, 4, -math.pi / 2)
47  actual = pose.transformFrom(Point2(2, 1))
48  expected = Point2(3, 2)
49  self.gtsamAssertEquals(actual, expected, 1e-6)
50 
51  # multi-point version
52  points = np.stack([Point2(2, 1), Point2(2, 1)]).T
53  actual_array = pose.transformFrom(points)
54  self.assertEqual(actual_array.shape, (2, 2))
55  expected_array = np.stack([expected, expected]).T
56  np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
57 
58  def test_align(self) -> None:
59  """Ensure estimation of the Pose2 element to align two 2d point clouds succeeds.
60 
61  Two point clouds represent horseshoe-shapes of the same size, just rotated and translated:
62 
63  | X---X
64  | |
65  | X---X
66  ------------------
67  |
68  |
69  O | O
70  | | |
71  O---O
72  """
73  pts_a = [
74  Point2(1, -3),
75  Point2(1, -5),
76  Point2(-1, -5),
77  Point2(-1, -3),
78  ]
79  pts_b = [
80  Point2(3, 1),
81  Point2(1, 1),
82  Point2(1, 3),
83  Point2(3, 3),
84  ]
85 
86  # fmt: on
87  ab_pairs = list(zip(pts_a, pts_b))
88  aTb = Pose2.Align(ab_pairs)
89  self.assertIsNotNone(aTb)
90 
91  for pt_a, pt_b in zip(pts_a, pts_b):
92  pt_a_ = aTb.transformFrom(pt_b)
93  np.testing.assert_allclose(pt_a, pt_a_)
94 
95  # Matrix version
96  A = np.array(pts_a).T
97  B = np.array(pts_b).T
98  aTb = Pose2.Align(A, B)
99  self.assertIsNotNone(aTb)
100 
101  for pt_a, pt_b in zip(pts_a, pts_b):
102  pt_a_ = aTb.transformFrom(pt_b)
103  np.testing.assert_allclose(pt_a, pt_a_)
104 
105 
106 if __name__ == "__main__":
107  unittest.main()
def test_transformTo(self)
Definition: test_Pose2.py:30
def test_transformFrom(self)
Definition: test_Pose2.py:44
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
Vector2 Point2
Definition: Point2.h:32
def test_align(self)
Definition: test_Pose2.py:58
def test_adjoint(self)
Definition: test_Pose2.py:23
Definition: pytypes.h:1979


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:37:46