add Python unit tests
parent
f5ec070f9f
commit
2ab09a580f
|
@ -279,7 +279,6 @@ virtual class GaussianFactor {
|
|||
virtual class JacobianFactor : gtsam::GaussianFactor {
|
||||
//Constructors
|
||||
JacobianFactor();
|
||||
JacobianFactor(const gtsam::GaussianFactor& factor);
|
||||
JacobianFactor(Vector b_in);
|
||||
JacobianFactor(size_t i1, Matrix A1, Vector b,
|
||||
const gtsam::noiseModel::Diagonal* model);
|
||||
|
@ -295,6 +294,7 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
|
|||
JacobianFactor(const gtsam::GaussianFactorGraph& graph,
|
||||
const gtsam::Ordering& ordering,
|
||||
const gtsam::VariableSlots& p_variableSlots);
|
||||
JacobianFactor(const gtsam::GaussianFactor& factor);
|
||||
|
||||
//Testable
|
||||
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
|
||||
|
|
|
@ -11,9 +11,8 @@ Author: Varun Agrawal
|
|||
"""
|
||||
import unittest
|
||||
|
||||
import numpy as np
|
||||
|
||||
import gtsam
|
||||
import numpy as np
|
||||
from gtsam.utils.test_case import GtsamTestCase
|
||||
|
||||
|
||||
|
@ -21,6 +20,7 @@ class TestNonlinearEquality2Factor(GtsamTestCase):
|
|||
"""
|
||||
Test various instantiations of NonlinearEquality2.
|
||||
"""
|
||||
|
||||
def test_point3(self):
|
||||
"""Test for Point3 version."""
|
||||
factor = gtsam.NonlinearEquality2Point3(0, 1)
|
||||
|
@ -30,5 +30,23 @@ class TestNonlinearEquality2Factor(GtsamTestCase):
|
|||
np.testing.assert_allclose(error, np.zeros(3))
|
||||
|
||||
|
||||
class TestJacobianFactor(GtsamTestCase):
|
||||
"""Test JacobianFactor"""
|
||||
|
||||
def test_gaussian_factor_graph(self):
|
||||
"""Test construction from GaussianFactorGraph."""
|
||||
gfg = gtsam.GaussianFactorGraph()
|
||||
jf = gtsam.JacobianFactor(gfg)
|
||||
self.assertIsInstance(jf, gtsam.JacobianFactor)
|
||||
|
||||
nfg = gtsam.NonlinearFactorGraph()
|
||||
nfg.push_back(gtsam.PriorFactorDouble(1, 0.0, gtsam.noiseModel.Isotropic.Sigma(1, 1.0)))
|
||||
values = gtsam.Values()
|
||||
values.insert(1, 0.0)
|
||||
gfg = nfg.linearize(values)
|
||||
jf = gtsam.JacobianFactor(gfg)
|
||||
self.assertIsInstance(jf, gtsam.JacobianFactor)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
|
|
|
@ -50,6 +50,34 @@ class TestSam(GtsamTestCase):
|
|||
self.assertEqual(range_measurement, measurement.range())
|
||||
self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
|
||||
|
||||
def test_BearingRangeFactor3D(self):
|
||||
"""
|
||||
Test that `measured` works as expected for BearingRangeFactor3D.
|
||||
"""
|
||||
bearing_measurement = gtsam.Unit3()
|
||||
range_measurement = 10.0
|
||||
factor = gtsam.BearingRangeFactor3D(
|
||||
1, 2, bearing_measurement, range_measurement,
|
||||
gtsam.noiseModel.Isotropic.Sigma(3, 1))
|
||||
measurement = factor.measured()
|
||||
|
||||
self.assertEqual(range_measurement, measurement.range())
|
||||
self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
|
||||
|
||||
def test_BearingRangeFactorPose3(self):
|
||||
"""
|
||||
Test that `measured` works as expected for BearingRangeFactorPose3.
|
||||
"""
|
||||
range_measurement = 10.0
|
||||
bearing_measurement = gtsam.Unit3()
|
||||
factor = gtsam.BearingRangeFactorPose3(
|
||||
1, 2, bearing_measurement, range_measurement,
|
||||
gtsam.noiseModel.Isotropic.Sigma(3, 1))
|
||||
measurement = factor.measured()
|
||||
|
||||
self.assertEqual(range_measurement, measurement.range())
|
||||
self.gtsamAssertEquals(bearing_measurement, measurement.bearing())
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
|
|
Loading…
Reference in New Issue