fix python tests
parent
1b7435361e
commit
1c74da26f4
|
@ -37,7 +37,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase):
|
||||||
jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model)
|
jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model)
|
||||||
jf2 = JacobianFactor(X(0), np.eye(3), np.ones((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 = HybridGaussianFactorGraph()
|
||||||
hfg.push_back(jf1)
|
hfg.push_back(jf1)
|
||||||
|
@ -64,7 +64,7 @@ class TestHybridGaussianFactorGraph(GtsamTestCase):
|
||||||
jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model)
|
jf1 = JacobianFactor(X(0), np.eye(3), np.zeros((3, 1)), model)
|
||||||
jf2 = JacobianFactor(X(0), np.eye(3), np.ones((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 = HybridGaussianFactorGraph()
|
||||||
hfg.push_back(jf1)
|
hfg.push_back(jf1)
|
||||||
|
|
|
@ -35,13 +35,12 @@ class TestHybridGaussianFactorGraph(GtsamTestCase):
|
||||||
nlfg.push_back(
|
nlfg.push_back(
|
||||||
PriorFactorPoint3(2, Point3(1, 2, 3),
|
PriorFactorPoint3(2, Point3(1, 2, 3),
|
||||||
noiseModel.Diagonal.Variances([0.5, 0.5, 0.5])))
|
noiseModel.Diagonal.Variances([0.5, 0.5, 0.5])))
|
||||||
nlfg.push_back(
|
|
||||||
gtsam.HybridNonlinearFactor([1], dk, [
|
factors = [(PriorFactorPoint3(1, Point3(0, 0, 0),
|
||||||
PriorFactorPoint3(1, Point3(0, 0, 0),
|
noiseModel.Unit.Create(3)), 0.0),
|
||||||
noiseModel.Unit.Create(3)),
|
(PriorFactorPoint3(1, Point3(1, 2, 1),
|
||||||
PriorFactorPoint3(1, Point3(1, 2, 1),
|
noiseModel.Unit.Create(3)), 0.0)]
|
||||||
noiseModel.Unit.Create(3))
|
nlfg.push_back(gtsam.HybridNonlinearFactor([1], dk, factors))
|
||||||
]))
|
|
||||||
nlfg.push_back(gtsam.DecisionTreeFactor((10, 2), "1 3"))
|
nlfg.push_back(gtsam.DecisionTreeFactor((10, 2), "1 3"))
|
||||||
values = gtsam.Values()
|
values = gtsam.Values()
|
||||||
values.insert_point3(1, Point3(0, 0, 0))
|
values.insert_point3(1, Point3(0, 0, 0))
|
||||||
|
|
Loading…
Reference in New Issue