2 Unit tests for optimization that logs to comet.ml. 3 Author: Jing Wu and Frank Dellaert 8 if sys.version_info.major >= 3:
9 from io
import StringIO
11 from cStringIO
import StringIO
14 from datetime
import datetime
18 from gtsam
import Rot3
28 """Check correct logging to comet.ml.""" 31 """Set up a small Karcher mean optimization example.""" 33 R = Rot3.Expmap(np.array([0.1, 0, 0]))
34 rotations = {R, R.inverse()}
39 graph.add(gtsam.PriorFactorRot3(KEY, R, MODEL))
41 initial.insert(KEY, R)
44 graph, initial, self.
params)
56 """Reset print capture.""" 57 sys.stdout = sys.__stdout__
60 """Test with a simple hook.""" 70 actual = self.optimizer.values()
74 """Make sure we are properly terminating LM""" 80 actual = self.lmoptimizer.values()
83 @unittest.skip(
"Not a test we want run every time, as needs comet.ml account")
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")
93 comet.set_name(
"GaussNewton-" +
str(time.month) +
"/" +
str(time.day) +
" " 94 +
str(time.hour)+
":"+
str(time.minute)+
":"+
str(time.second))
97 def hook(optimizer, error):
98 comet.log_metric(
"Karcher error",
99 error, optimizer.iterations())
104 actual = self.optimizer.values()
107 if __name__ ==
"__main__":
void print(const Matrix &A, const string &s, ostream &stream)
def gtsam_optimize(optimizer, params, hook)
def gtsamAssertEquals(self, actual, expected, tol=1e-9)
static shared_ptr Create(size_t dim)
def test_simple_printing(self)
def test_lm_simple_printing(self)