test_logging_optimizer.py
Go to the documentation of this file.
1 """
2 Unit tests for optimization that logs to comet.ml.
3 Author: Jing Wu and Frank Dellaert
4 """
5 # pylint: disable=invalid-name
6 
7 import sys
8 if sys.version_info.major >= 3:
9  from io import StringIO
10 else:
11  from cStringIO import StringIO
12 
13 import unittest
14 from datetime import datetime
15 
16 import gtsam
17 import numpy as np
18 from gtsam import Rot3
19 from gtsam.utils.test_case import GtsamTestCase
20 
21 from gtsam.utils.logging_optimizer import gtsam_optimize, optimize_using
22 
23 KEY = 0
25 
26 
28  """Check correct logging to comet.ml."""
29 
30  def setUp(self):
31  """Set up a small Karcher mean optimization example."""
32  # Grabbed from KarcherMeanFactor unit tests.
33  R = Rot3.Expmap(np.array([0.1, 0, 0]))
34  rotations = {R, R.inverse()} # mean is the identity
35  self.expected = Rot3()
36 
37  def check(actual):
38  # Check that optimizing yields the identity
39  self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6)
40  # Check that logging output prints out 3 lines (exact intermediate values differ by OS)
41  self.assertEqual(self.capturedOutput.getvalue().count('\n'), 3)
42  # reset stdout catcher
43  self.capturedOutput.truncate(0)
44  self.check = check
45 
47  for R in rotations:
48  self.graph.add(gtsam.PriorFactorRot3(KEY, R, MODEL))
50  self.initial.insert(KEY, R)
51 
52  # setup output capture
53  self.capturedOutput = StringIO()
54  sys.stdout = self.capturedOutput
55 
56  def tearDown(self):
57  """Reset print capture."""
58  sys.stdout = sys.__stdout__
59 
61  """Test with a simple hook."""
62 
63  # Provide a hook that just prints
64  def hook(_, error):
65  print(error)
66 
67  # Wrapper function sets the hook and calls optimizer.optimize() for us.
68  params = gtsam.GaussNewtonParams()
69  actual = optimize_using(gtsam.GaussNewtonOptimizer, hook, self.graph, self.initial)
70  self.check(actual)
71  actual = optimize_using(gtsam.GaussNewtonOptimizer, hook, self.graph, self.initial, params)
72  self.check(actual)
73  actual = gtsam_optimize(gtsam.GaussNewtonOptimizer(self.graph, self.initial, params),
74  params, hook)
75  self.check(actual)
76 
78  """Make sure we are properly terminating LM"""
79  def hook(_, error):
80  print(error)
81 
84  self.check(actual)
86  params)
87  self.check(actual)
89  params, hook)
90 
91  @unittest.skip("Not a test we want run every time, as needs comet.ml account")
92  def test_comet(self):
93  """Test with a comet hook."""
94  from comet_ml import Experiment
95  comet = Experiment(project_name="Testing",
96  auto_output_logging="native")
97  comet.log_dataset_info(name="Karcher", path="shonan")
98  comet.add_tag("GaussNewton")
99  comet.log_parameter("method", "GaussNewton")
100  time = datetime.now()
101  comet.set_name("GaussNewton-" + str(time.month) + "/" + str(time.day) + " "
102  + str(time.hour)+":"+str(time.minute)+":"+str(time.second))
103 
104  # I want to do some comet thing here
105  def hook(optimizer, error):
106  comet.log_metric("Karcher error",
107  error, optimizer.iterations())
108 
109  gtsam_optimize(self.optimizer, self.params, hook)
110  comet.end()
111 
112  actual = self.optimizer.values()
113  self.gtsamAssertEquals(actual.atRot3(KEY), self.expected)
114 
115 if __name__ == "__main__":
116  unittest.main()
test_logging_optimizer.TestOptimizeComet.test_lm_simple_printing
def test_lm_simple_printing(self)
Definition: test_logging_optimizer.py:77
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
gtsam::GaussNewtonOptimizer
Definition: GaussNewtonOptimizer.h:38
gtsam::utils.logging_optimizer
Definition: logging_optimizer.py:1
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
test_logging_optimizer.TestOptimizeComet.test_comet
def test_comet(self)
Definition: test_logging_optimizer.py:92
gtsam::utils.test_case.GtsamTestCase.gtsamAssertEquals
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
test_logging_optimizer.TestOptimizeComet.tearDown
def tearDown(self)
Definition: test_logging_optimizer.py:56
test_logging_optimizer.TestOptimizeComet.graph
graph
Definition: test_logging_optimizer.py:46
test_logging_optimizer.TestOptimizeComet.capturedOutput
capturedOutput
Definition: test_logging_optimizer.py:53
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
test_logging_optimizer.TestOptimizeComet.check
check
Definition: test_logging_optimizer.py:44
gtsam::GaussNewtonParams
Definition: GaussNewtonOptimizer.h:30
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
add
graph add(PriorFactor< Pose2 >(1, priorMean, priorNoise))
gtsam::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:631
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
test_logging_optimizer.TestOptimizeComet.test_simple_printing
def test_simple_printing(self)
Definition: test_logging_optimizer.py:60
gtsam::utils.test_case
Definition: test_case.py:1
test_logging_optimizer.TestOptimizeComet
Definition: test_logging_optimizer.py:27
str
Definition: pytypes.h:1558
gtsam::Values
Definition: Values.h:65
gtsam::utils.test_case.GtsamTestCase
Definition: test_case.py:15
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
test_logging_optimizer.TestOptimizeComet.setUp
def setUp(self)
Definition: test_logging_optimizer.py:30
test_logging_optimizer.TestOptimizeComet.expected
expected
Definition: test_logging_optimizer.py:35
insert
A insert(1, 2)=0
test_logging_optimizer.TestOptimizeComet.initial
initial
Definition: test_logging_optimizer.py:49
gtsam::utils.logging_optimizer.gtsam_optimize
def gtsam_optimize(optimizer, params, hook)
Definition: logging_optimizer.py:83
gtsam::utils.logging_optimizer.optimize_using
gtsam.Values optimize_using(OptimizerClass, hook, *args)
Definition: logging_optimizer.py:20


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:05