test_Utilities.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 Utilities unit tests.
9 Author: Varun Agrawal
10 """
11 # pylint: disable=invalid-name, E1101, E0611
12 import unittest
13 
14 import numpy as np
15 
16 import gtsam
17 from gtsam.utils.test_case import GtsamTestCase
18 
19 
21  """Test various GTSAM utilities."""
22  def test_createKeyList(self):
23  """Test createKeyList."""
24  I = [0, 1, 2]
26  self.assertEqual(kl.size(), 3)
27 
29  self.assertEqual(kl.size(), 3)
30 
32  """Test createKeyVector."""
33  I = [0, 1, 2]
35  self.assertEqual(len(kl), 3)
36 
38  self.assertEqual(len(kl), 3)
39 
40  def test_createKeySet(self):
41  """Test createKeySet."""
42  I = [0, 1, 2]
44  self.assertEqual(kl.size(), 3)
45 
46  kl = gtsam.utilities.createKeySet("s", I)
47  self.assertEqual(kl.size(), 3)
48 
49  def test_extractPoint2(self):
50  """Test extractPoint2."""
51  initial = gtsam.Values()
52  point2 = gtsam.Point2(0.0, 0.1)
53  initial.insert(1, gtsam.Pose2(0.0, 0.1, 0.1))
54  initial.insert(2, point2)
55  np.testing.assert_equal(gtsam.utilities.extractPoint2(initial),
56  point2.reshape(-1, 2))
57 
58  def test_extractPoint3(self):
59  """Test extractPoint3."""
60  initial = gtsam.Values()
61  point3 = gtsam.Point3(0.0, 0.1, 0.0)
62  initial.insert(1, gtsam.Pose2(0.0, 0.1, 0.1))
63  initial.insert(2, point3)
64  np.testing.assert_equal(gtsam.utilities.extractPoint3(initial),
65  point3.reshape(-1, 3))
66 
67  def test_allPose2s(self):
68  """Test allPose2s."""
69  initial = gtsam.Values()
70  initial.insert(0, gtsam.Pose2())
71  initial.insert(1, gtsam.Pose2(1, 1, 1))
72  initial.insert(2, gtsam.Point2(1, 1))
73  initial.insert(3, gtsam.Point3(1, 2, 3))
74  result = gtsam.utilities.allPose2s(initial)
75  self.assertEqual(result.size(), 2)
76 
77  def test_extractPose2(self):
78  """Test extractPose2."""
79  initial = gtsam.Values()
80  pose2 = np.asarray((0.0, 0.1, 0.1))
81 
82  initial.insert(1, gtsam.Pose2(*pose2))
83  initial.insert(2, gtsam.Point3(0.0, 0.1, 0.0))
84  np.testing.assert_allclose(gtsam.utilities.extractPose2(initial),
85  pose2.reshape(-1, 3))
86 
87  def test_allPose3s(self):
88  """Test allPose3s."""
89  initial = gtsam.Values()
90  initial.insert(0, gtsam.Pose3())
91  initial.insert(2, gtsam.Point2(1, 1))
92  initial.insert(1, gtsam.Pose3())
93  initial.insert(3, gtsam.Point3(1, 2, 3))
94  result = gtsam.utilities.allPose3s(initial)
95  self.assertEqual(result.size(), 2)
96 
97  def test_extractPose3(self):
98  """Test extractPose3."""
99  initial = gtsam.Values()
100  pose3 = np.asarray([1., 0., 0., 0., 1., 0., 0., 0., 1., 0., 0., 0.])
101  initial.insert(1, gtsam.Pose2(0.0, 0.1, 0.1))
102  initial.insert(2, gtsam.Pose3())
103  np.testing.assert_allclose(gtsam.utilities.extractPose3(initial),
104  pose3.reshape(-1, 12))
105 
107  """Test perturbPoint2."""
108  values = gtsam.Values()
109  values.insert(0, gtsam.Pose3())
110  values.insert(1, gtsam.Point2(1, 1))
111  gtsam.utilities.perturbPoint2(values, 1.0)
112  self.assertTrue(
113  not np.allclose(values.atPoint2(1), gtsam.Point2(1, 1)))
114 
115  def test_perturbPose2(self):
116  """Test perturbPose2."""
117  values = gtsam.Values()
118  values.insert(0, gtsam.Pose2())
119  values.insert(1, gtsam.Point2(1, 1))
120  gtsam.utilities.perturbPose2(values, 1, 1)
121  self.assertTrue(values.atPose2(0) != gtsam.Pose2())
122 
124  """Test perturbPoint3."""
125  values = gtsam.Values()
126  point3 = gtsam.Point3(0, 0, 0)
127  values.insert(0, gtsam.Pose2())
128  values.insert(1, point3)
130  self.assertTrue(not np.allclose(values.atPoint3(1), point3))
131 
133  """Test insertBackprojections."""
134  values = gtsam.Values()
137  values, cam, [0, 1, 2], np.asarray([[20, 30, 40], [20, 30, 40]]),
138  10)
139  np.testing.assert_allclose(values.atPoint3(0),
140  gtsam.Point3(200, 200, 10))
141 
143  """Test insertProjectionFactors."""
146  graph, 0, [0, 1], np.asarray([[20, 30], [20, 30]]),
148  self.assertEqual(graph.size(), 2)
149 
152  graph, 0, [0, 1], np.asarray([[20, 30], [20, 30]]),
154  gtsam.Pose3(gtsam.Rot3(), gtsam.Point3(1, 0, 0)))
155  self.assertEqual(graph.size(), 2)
156 
158  """Test reprojectionErrors."""
159  pixels = np.asarray([[20, 30], [20, 30]])
160  I = [1, 2]
161  K = gtsam.Cal3_S2()
164  graph, 0, I, pixels, gtsam.noiseModel.Isotropic.Sigma(2, 0.1), K)
165  values = gtsam.Values()
166  values.insert(0, gtsam.Pose3())
168  gtsam.utilities.insertBackprojections(values, cam, I, pixels, 10)
169  errors = gtsam.utilities.reprojectionErrors(graph, values)
170  np.testing.assert_allclose(errors, np.zeros((2, 2)))
171 
172  def test_localToWorld(self):
173  """Test localToWorld."""
174  local = gtsam.Values()
175  local.insert(0, gtsam.Point2(10, 10))
176  local.insert(1, gtsam.Pose2(6, 11, 0.0))
177  base = gtsam.Pose2(1, 0, 0)
178  world = gtsam.utilities.localToWorld(local, base)
179 
180  expected_point2 = gtsam.Point2(11, 10)
181  expected_pose2 = gtsam.Pose2(7, 11, 0)
182  np.testing.assert_allclose(world.atPoint2(0), expected_point2)
183  np.testing.assert_allclose(
184  world.atPose2(1).matrix(), expected_pose2.matrix())
185 
186  user_keys = [1]
187  world = gtsam.utilities.localToWorld(local, base, user_keys)
188  np.testing.assert_allclose(
189  world.atPose2(1).matrix(), expected_pose2.matrix())
190 
191  # Raise error since 0 is not in user_keys
192  self.assertRaises(RuntimeError, world.atPoint2, 0)
193 
194 
195 if __name__ == "__main__":
196  unittest.main()
void perturbPose2(Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
Perturb all Pose2 values using normally distributed noise.
FastList< Key > createKeyList(std::string s, const Vector &I)
void insertBackprojections(Values &values, const PinholeCamera< Cal3_S2 > &camera, const Vector &J, const Matrix &Z, double depth)
Insert a number of initial point values by backprojecting.
Vector2 Point2
Definition: Point2.h:32
void perturbPoint2(Values &values, double sigma, int32_t seed=42u)
Perturb all Point2 values using normally distributed noise.
Matrix reprojectionErrors(const NonlinearFactorGraph &graph, const Values &values)
Calculate the errors of all projection factors in a graph.
Matrix extractPose3(const Values &values)
Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z]...
KeyVector createKeyVector(std::string s, const Vector &I)
void insertProjectionFactors(NonlinearFactorGraph &graph, Key i, const Vector &J, const Matrix &Z, const SharedNoiseModel &model, const Cal3_S2::shared_ptr K, const Pose3 &body_P_sensor=Pose3())
Insert multiple projection factors for a single pose key.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
Matrix extractPoint2(const Values &values)
Extract all Point2 values into a single matrix [x y].
KeySet createKeySet(std::string s, const Vector &I)
void perturbPoint3(Values &values, double sigma, int32_t seed=42u)
Perturb all Point3 values using normally distributed noise.
Values allPose3s(const Values &values)
Extract all Pose3 values.
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
Values allPose2s(const Values &values)
Extract all Pose3 values.
Matrix extractPose2(const Values &values)
Extract all Pose2 values into a single matrix [x y theta].
Vector3 Point3
Definition: Point3.h:38
Values localToWorld(const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
Convert from local to world coordinates.
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2244
Matrix extractPoint3(const Values &values)
Extract all Point3 values into a single matrix [x y z].
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


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