2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 Unit tests for Shonan Rotation Averaging. 19 from gtsam
import (BetweenFactorPose2, LevenbergMarquardtParams, Pose2, Rot2,
20 ShonanAveraging2, ShonanAveraging3,
21 ShonanAveragingParameters2, ShonanAveragingParameters3)
29 name: str, parameters: ShonanAveragingParameters3 = DEFAULT_PARAMS
30 ) -> ShonanAveraging3:
32 return ShonanAveraging3(g2oFile, parameters)
36 """Tests for Shonan Rotation Averaging.""" 39 """Set up common variables.""" 43 self.assertEqual(5, self.
shonan.nrUnknowns())
46 self.assertEqual((15, 15), D.shape)
49 self.assertEqual((15, 15), Q.shape)
52 self.assertEqual((15, 15), L.shape)
55 graph = self.
shonan.buildGraphAt(5)
56 self.assertEqual(7, graph.size())
59 random = self.
shonan.initializeRandomlyAt(4)
60 lambdaMin = self.
shonan.computeMinEigenValue(random)
61 self.assertAlmostEqual(-414.87376657555996,
63 self.assertFalse(self.
shonan.checkOptimality(random))
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,
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)
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,
85 SO3Values = self.
shonan.roundSolution(result)
86 self.assertAlmostEqual(0, self.
shonan.cost(SO3Values), places=3)
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())
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,
110 self.assertAlmostEqual(4, shonan.nrUnknowns())
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)
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)
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)
145 """Check if ShonanAveraging2 constructor works when not initialized from g2o file. 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])),
167 edges = [(0, 1), (1, 2), (0, 2)]
170 for (i1, i2)
in edges
173 lm_params = LevenbergMarquardtParams.CeresDefaults()
175 shonan_params.setUseHuber(
False)
176 shonan_params.setCertifyOptimality(
True)
180 for (i1, i2), i2Ri1
in i2Ri1_dict.items():
181 i2Ti1 = Pose2(i2Ri1, np.zeros(2))
182 between_factors.append(
186 obj = ShonanAveraging2(between_factors, shonan_params)
187 initial = obj.initializeRandomly()
188 result_values, _ = obj.run(initial, min_p=2, max_p=100)
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])
194 thetas_deg = thetas_deg % 360
195 thetas_deg -= thetas_deg[0]
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)
201 if __name__ ==
"__main__":
def test_checkConstructor(self)
def test_tryOptimizingAt3(self)
def test_PriorWeights(self)
def test_constructorBetweenFactorPose2s(self)
static LevenbergMarquardtParams CeresDefaults()
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
static shared_ptr Create(size_t dim)
T compose(const T &t1, const T &t2)
ShonanAveragingParameters< 2 > ShonanAveragingParameters2
Parameters governing optimization etc.
def test_tryOptimizingAt4(self)
def test_initializeWithDescent(self)
ShonanAveragingParameters< 3 > ShonanAveragingParameters3
def test_checkOptimality(self)
def test_buildGraphAt(self)
GTSAM_EXPORT std::string findExampleDataFile(const std::string &name)
Double_ range(const Point2_ &p, const Point2_ &q)
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
def test_runKlausKarcher(self)