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
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 
38  for R in rotations:
39  graph.add(gtsam.PriorFactorRot3(KEY, R, MODEL))
40  initial = gtsam.Values()
41  initial.insert(KEY, R)
44  graph, initial, self.params)
45 
48  graph, initial, self.lmparams
49  )
50 
51  # setup output capture
52  self.capturedOutput = StringIO()
53  sys.stdout = self.capturedOutput
54 
55  def tearDown(self):
56  """Reset print capture."""
57  sys.stdout = sys.__stdout__
58 
60  """Test with a simple hook."""
61 
62  # Provide a hook that just prints
63  def hook(_, error):
64  print(error)
65 
66  # Only thing we require from optimizer is an iterate method
67  gtsam_optimize(self.optimizer, self.params, hook)
68 
69  # Check that optimizing yields the identity.
70  actual = self.optimizer.values()
71  self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6)
72 
74  """Make sure we are properly terminating LM"""
75  def hook(_, error):
76  print(error)
77 
78  gtsam_optimize(self.lmoptimizer, self.lmparams, hook)
79 
80  actual = self.lmoptimizer.values()
81  self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6)
82 
83  @unittest.skip("Not a test we want run every time, as needs comet.ml account")
84  def test_comet(self):
85  """Test with a comet hook."""
86  from comet_ml import Experiment
87  comet = Experiment(project_name="Testing",
88  auto_output_logging="native")
89  comet.log_dataset_info(name="Karcher", path="shonan")
90  comet.add_tag("GaussNewton")
91  comet.log_parameter("method", "GaussNewton")
92  time = datetime.now()
93  comet.set_name("GaussNewton-" + str(time.month) + "/" + str(time.day) + " "
94  + str(time.hour)+":"+str(time.minute)+":"+str(time.second))
95 
96  # I want to do some comet thing here
97  def hook(optimizer, error):
98  comet.log_metric("Karcher error",
99  error, optimizer.iterations())
100 
101  gtsam_optimize(self.optimizer, self.params, hook)
102  comet.end()
103 
104  actual = self.optimizer.values()
105  self.gtsamAssertEquals(actual.atRot3(KEY), self.expected)
106 
107 if __name__ == "__main__":
108  unittest.main()
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
def gtsam_optimize(optimizer, params, hook)
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
Definition: test_case.py:18
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:608
Definition: pytypes.h:928


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:03