test_ShonanAveraging.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 Unit tests for Shonan Rotation Averaging.
9 Author: Frank Dellaert
10 """
11 # pylint: disable=invalid-name, no-name-in-module, no-member
12 
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 (BetweenFactorPose2, LevenbergMarquardtParams, Pose2, Rot2,
20  ShonanAveraging2, ShonanAveraging3,
21  ShonanAveragingParameters2, ShonanAveragingParameters3)
22 
23 DEFAULT_PARAMS = ShonanAveragingParameters3(
25 )
26 
27 
28 def fromExampleName(
29  name: str, parameters: ShonanAveragingParameters3 = DEFAULT_PARAMS
30 ) -> ShonanAveraging3:
31  g2oFile = gtsam.findExampleDataFile(name)
32  return ShonanAveraging3(g2oFile, parameters)
33 
34 
36  """Tests for Shonan Rotation Averaging."""
37 
38  def setUp(self):
39  """Set up common variables."""
40  self.shonan = fromExampleName("toyExample.g2o")
41 
43  self.assertEqual(5, self.shonan.nrUnknowns())
44 
45  D = self.shonan.denseD()
46  self.assertEqual((15, 15), D.shape)
47 
48  Q = self.shonan.denseQ()
49  self.assertEqual((15, 15), Q.shape)
50 
51  L = self.shonan.denseL()
52  self.assertEqual((15, 15), L.shape)
53 
54  def test_buildGraphAt(self):
55  graph = self.shonan.buildGraphAt(5)
56  self.assertEqual(7, graph.size())
57 
59  random = self.shonan.initializeRandomlyAt(4)
60  lambdaMin = self.shonan.computeMinEigenValue(random)
61  self.assertAlmostEqual(-414.87376657555996,
62  lambdaMin, places=3) # Regression test
63  self.assertFalse(self.shonan.checkOptimality(random))
64 
66  initial = self.shonan.initializeRandomlyAt(3)
67  self.assertFalse(self.shonan.checkOptimality(initial))
68  result = self.shonan.tryOptimizingAt(3, initial)
69  self.assertTrue(self.shonan.checkOptimality(result))
70  lambdaMin = self.shonan.computeMinEigenValue(result)
71  self.assertAlmostEqual(-5.427688831332745e-07,
72  lambdaMin, places=3) # Regression test
73  self.assertAlmostEqual(0, self.shonan.costAt(3, result), places=3)
74  SO3Values = self.shonan.roundSolution(result)
75  self.assertAlmostEqual(0, self.shonan.cost(SO3Values), places=3)
76 
78  random = self.shonan.initializeRandomlyAt(4)
79  result = self.shonan.tryOptimizingAt(4, random)
80  self.assertTrue(self.shonan.checkOptimality(result))
81  self.assertAlmostEqual(0, self.shonan.costAt(4, result), places=2)
82  lambdaMin = self.shonan.computeMinEigenValue(result)
83  self.assertAlmostEqual(-5.427688831332745e-07,
84  lambdaMin, places=3) # Regression test
85  SO3Values = self.shonan.roundSolution(result)
86  self.assertAlmostEqual(0, self.shonan.cost(SO3Values), places=3)
87 
89  random = self.shonan.initializeRandomlyAt(3)
90  Qstar3 = self.shonan.tryOptimizingAt(3, random)
91  lambdaMin, minEigenVector = self.shonan.computeMinEigenVector(Qstar3)
92  initialQ4 = self.shonan.initializeWithDescent(
93  4, Qstar3, minEigenVector, lambdaMin)
94  self.assertAlmostEqual(5, initialQ4.size())
95 
96  def test_run(self):
97  initial = self.shonan.initializeRandomly()
98  result, lambdaMin = self.shonan.run(initial, 5, 10)
99  self.assertAlmostEqual(0, self.shonan.cost(result), places=2)
100  self.assertAlmostEqual(-5.427688831332745e-07,
101  lambdaMin, places=3) # Regression test
102 
104  # Load 2D toy example
106  # lmParams.setVerbosityLM("SUMMARY")
107  g2oFile = gtsam.findExampleDataFile("noisyToyGraph.txt")
108  parameters = gtsam.ShonanAveragingParameters2(lmParams)
109  shonan = gtsam.ShonanAveraging2(g2oFile, parameters)
110  self.assertAlmostEqual(4, shonan.nrUnknowns())
111 
112  # Check graph building
113  graph = shonan.buildGraphAt(2)
114  self.assertAlmostEqual(6, graph.size())
115  initial = shonan.initializeRandomly()
116  result, lambdaMin = shonan.run(initial, 2, 10)
117  self.assertAlmostEqual(0.0008211, shonan.cost(result), places=5)
118  self.assertAlmostEqual(0, lambdaMin, places=9) # certificate!
119 
120  # Test alpha/beta/gamma prior weighting.
121  def test_PriorWeights(self):
123  params = ShonanAveragingParameters3(lmParams)
124  self.assertAlmostEqual(0, params.getAnchorWeight(), 1e-9)
125  self.assertAlmostEqual(1, params.getKarcherWeight(), 1e-9)
126  self.assertAlmostEqual(0, params.getGaugesWeight(), 1e-9)
127  alpha, beta, gamma = 100.0, 200.0, 300.0
128  params.setAnchorWeight(alpha)
129  params.setKarcherWeight(beta)
130  params.setGaugesWeight(gamma)
131  self.assertAlmostEqual(alpha, params.getAnchorWeight(), 1e-9)
132  self.assertAlmostEqual(beta, params.getKarcherWeight(), 1e-9)
133  self.assertAlmostEqual(gamma, params.getGaugesWeight(), 1e-9)
134  params.setKarcherWeight(0)
135  shonan = fromExampleName("Klaus3.g2o", params)
136 
137  initial = gtsam.Values()
138  for i in range(3):
139  initial.insert(i, gtsam.Rot3())
140  self.assertAlmostEqual(3.0756, shonan.cost(initial), places=3)
141  result, _lambdaMin = shonan.run(initial, 3, 3)
142  self.assertAlmostEqual(0.0015, shonan.cost(result), places=3)
143 
145  """Check if ShonanAveraging2 constructor works when not initialized from g2o file.
146 
147  GT pose graph:
148 
149  | cam 1 = (0,4)
150  --o
151  | .
152  . .
153  . .
154  | |
155  o-- ... o--
156  cam 0 cam 2 = (4,0)
157  (0,0)
158  """
159  num_images = 3
160 
161  wTi_list = [
162  Pose2(Rot2.fromDegrees(0), np.array([0, 0])),
163  Pose2(Rot2.fromDegrees(90), np.array([0, 4])),
164  Pose2(Rot2.fromDegrees(0), np.array([4, 0])),
165  ]
166 
167  edges = [(0, 1), (1, 2), (0, 2)]
168  i2Ri1_dict = {
169  (i1, i2): wTi_list[i2].inverse().compose(wTi_list[i1]).rotation()
170  for (i1, i2) in edges
171  }
172 
173  lm_params = LevenbergMarquardtParams.CeresDefaults()
174  shonan_params = ShonanAveragingParameters2(lm_params)
175  shonan_params.setUseHuber(False)
176  shonan_params.setCertifyOptimality(True)
177 
178  noise_model = gtsam.noiseModel.Unit.Create(3)
179  between_factors = []
180  for (i1, i2), i2Ri1 in i2Ri1_dict.items():
181  i2Ti1 = Pose2(i2Ri1, np.zeros(2))
182  between_factors.append(
183  BetweenFactorPose2(i2, i1, i2Ti1, noise_model)
184  )
185 
186  obj = ShonanAveraging2(between_factors, shonan_params)
187  initial = obj.initializeRandomly()
188  result_values, _ = obj.run(initial, min_p=2, max_p=100)
189 
190  wRi_list = [result_values.atRot2(i) for i in range(num_images)]
191  thetas_deg = np.array([wRi.degrees() for wRi in wRi_list])
192 
193  # map all angles to [0,360)
194  thetas_deg = thetas_deg % 360
195  thetas_deg -= thetas_deg[0]
196 
197  expected_thetas_deg = np.array([0.0, 90.0, 0.0])
198  np.testing.assert_allclose(thetas_deg, expected_thetas_deg, atol=0.1)
199 
200 
201 if __name__ == "__main__":
202  unittest.main()
static LevenbergMarquardtParams CeresDefaults()
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:610
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
ShonanAveragingParameters< 2 > ShonanAveragingParameters2
Parameters governing optimization etc.
ShonanAveragingParameters< 3 > ShonanAveragingParameters3
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Definition: dataset.cpp:70
Double_ range(const Point2_ &p, const Point2_ &q)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)


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