From 1c74da26f455a3f12b692eecfc5142ab463449a5 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 15 Sep 2024 09:46:33 -0400 Subject: [PATCH] fix python tests --- python/gtsam/tests/test_HybridFactorGraph.py | 4 ++-- .../gtsam/tests/test_HybridNonlinearFactorGraph.py | 13 ++++++------- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/python/gtsam/tests/test_HybridFactorGraph.py b/python/gtsam/tests/test_HybridFactorGraph.py index f82665c49..adbda59ce 100644 --- a/python/gtsam/tests/test_HybridFactorGraph.py +++ b/python/gtsam/tests/test_HybridFactorGraph.py @@ -37,7 +37,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase): jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model) jf2 = JacobianFactor(X(0), np.eye(3), np.ones((3, 1)), model) - gmf = HybridGaussianFactor([X(0)], dk, [jf1, jf2]) + gmf = HybridGaussianFactor([X(0)], dk, [(jf1, 0), (jf2, 0)]) hfg = HybridGaussianFactorGraph() hfg.push_back(jf1) @@ -64,7 +64,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase): jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model) jf2 = JacobianFactor(X(0), np.eye(3), np.ones((3, 1)), model) - gmf = HybridGaussianFactor([X(0)], dk, [jf1, jf2]) + gmf = HybridGaussianFactor([X(0)], dk, [(jf1, 0), (jf2, 0)]) hfg = HybridGaussianFactorGraph() hfg.push_back(jf1) diff --git a/python/gtsam/tests/test_HybridNonlinearFactorGraph.py b/python/gtsam/tests/test_HybridNonlinearFactorGraph.py index 3a659c4e8..247f83c19 100644 --- a/python/gtsam/tests/test_HybridNonlinearFactorGraph.py +++ b/python/gtsam/tests/test_HybridNonlinearFactorGraph.py @@ -35,13 +35,12 @@ class TestHybridGaussianFactorGraph(GtsamTestCase): nlfg.push_back( PriorFactorPoint3(2, Point3(1, 2, 3), noiseModel.Diagonal.Variances([0.5, 0.5, 0.5]))) - nlfg.push_back( - gtsam.HybridNonlinearFactor([1], dk, [ - PriorFactorPoint3(1, Point3(0, 0, 0), - noiseModel.Unit.Create(3)), - PriorFactorPoint3(1, Point3(1, 2, 1), - noiseModel.Unit.Create(3)) - ])) + + factors = [(PriorFactorPoint3(1, Point3(0, 0, 0), + noiseModel.Unit.Create(3)), 0.0), + (PriorFactorPoint3(1, Point3(1, 2, 1), + noiseModel.Unit.Create(3)), 0.0)] + nlfg.push_back(gtsam.HybridNonlinearFactor([1], dk, factors)) nlfg.push_back(gtsam.DecisionTreeFactor((10, 2), "1 3")) values = gtsam.Values() values.insert_point3(1, Point3(0, 0, 0))