Modernized all tests

release/4.3a0
Frank Dellaert 2019-03-20 17:35:53 -04:00
parent 90e6eb95cf
commit c442df3866
21 changed files with 316 additions and 93 deletions

View File

@ -1,9 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Cal3Unified unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestCal3Unified(unittest.TestCase):
class TestCal3Unified(GtsamTestCase):
def test_Cal3Unified(self): def test_Cal3Unified(self):
K = gtsam.Cal3Unified() K = gtsam.Cal3Unified()
@ -11,12 +24,15 @@ class TestCal3Unified(unittest.TestCase):
self.assertEqual(K.fx(), 1.) self.assertEqual(K.fx(), 1.)
def test_retract(self): def test_retract(self):
expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6, 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1) expected = gtsam.Cal3Unified(100 + 2, 105 + 3, 0.0 + 4, 320 + 5, 240 + 6,
K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240, 1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1) 1e-3 + 7, 2.0*1e-3 + 8, 3.0*1e-3 + 9, 4.0*1e-3 + 10, 0.1 + 1)
K = gtsam.Cal3Unified(100, 105, 0.0, 320, 240,
1e-3, 2.0*1e-3, 3.0*1e-3, 4.0*1e-3, 0.1)
d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10, 1], order='F') d = np.array([2, 3, 4, 5, 6, 7, 8, 9, 10, 1], order='F')
actual = K.retract(d) actual = K.retract(d)
self.assertTrue(actual.equals(expected, 1e-9)) self.gtsamAssertEquals(actual, expected)
np.testing.assert_allclose(d, K.localCoordinates(actual)) np.testing.assert_allclose(d, K.localCoordinates(actual))
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -1,8 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
JacobianFactor unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
class TestJacobianFactor(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestJacobianFactor(GtsamTestCase):
def test_eliminate(self): def test_eliminate(self):
# Recommended way to specify a matrix (see cython/README) # Recommended way to specify a matrix (see cython/README)
@ -54,7 +68,7 @@ class TestJacobianFactor(unittest.TestCase):
expectedCG = gtsam.GaussianConditional( expectedCG = gtsam.GaussianConditional(
x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel_Unit.Create(2)) x2, d, R11, l1, S12, x1, S13, gtsam.noiseModel_Unit.Create(2))
# check if the result matches # check if the result matches
self.assertTrue(actualCG.equals(expectedCG, 1e-4)) self.gtsamAssertEquals(actualCG, expectedCG, 1e-4)
# the expected linear factor # the expected linear factor
Bl1 = np.array([[4.47214, 0.00], Bl1 = np.array([[4.47214, 0.00],
@ -72,7 +86,7 @@ class TestJacobianFactor(unittest.TestCase):
expectedLF = gtsam.JacobianFactor(l1, Bl1, x1, Bx1, b1, model2) expectedLF = gtsam.JacobianFactor(l1, Bl1, x1, Bx1, b1, model2)
# check if the result matches the combined (reduced) factor # check if the result matches the combined (reduced) factor
self.assertTrue(lf.equals(expectedLF, 1e-4)) self.gtsamAssertEquals(lf, expectedLF, 1e-4)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -1,8 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
KalmanFilter unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
class TestKalmanFilter(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestKalmanFilter(GtsamTestCase):
def test_KalmanFilter(self): def test_KalmanFilter(self):
F = np.eye(2) F = np.eye(2)

View File

@ -1,8 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Localization unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
class TestLocalizationExample(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestLocalizationExample(GtsamTestCase):
def test_LocalizationExample(self): def test_LocalizationExample(self):
# Create the graph (defined in pose2SLAM.h, derived from # Create the graph (defined in pose2SLAM.h, derived from
@ -43,7 +57,7 @@ class TestLocalizationExample(unittest.TestCase):
P = [None] * result.size() P = [None] * result.size()
for i in range(0, result.size()): for i in range(0, result.size()):
pose_i = result.atPose2(i) pose_i = result.atPose2(i)
self.assertTrue(pose_i.equals(groundTruth.atPose2(i), 1e-4)) self.gtsamAssertEquals(pose_i, groundTruth.atPose2(i), 1e-4)
P[i] = marginals.marginalCovariance(i) P[i] = marginals.marginalCovariance(i)
if __name__ == "__main__": if __name__ == "__main__":

View File

@ -19,12 +19,13 @@ from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer,
GaussNewtonParams, LevenbergMarquardtOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer,
LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, LevenbergMarquardtParams, NonlinearFactorGraph, Ordering,
Point2, PriorFactorPoint2, Values) Point2, PriorFactorPoint2, Values)
from gtsam.utils.test_case import GtsamTestCase
KEY1 = 1 KEY1 = 1
KEY2 = 2 KEY2 = 2
class TestScenario(unittest.TestCase): class TestScenario(GtsamTestCase):
def test_optimize(self): def test_optimize(self):
"""Do trivial test with three optimizer variants.""" """Do trivial test with three optimizer variants."""
fg = NonlinearFactorGraph() fg = NonlinearFactorGraph()

View File

@ -1,8 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Odometry unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
class TestOdometryExample(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestOdometryExample(GtsamTestCase):
def test_OdometryExample(self): def test_OdometryExample(self):
# Create the graph (defined in pose2SLAM.h, derived from # Create the graph (defined in pose2SLAM.h, derived from
@ -39,7 +53,7 @@ class TestOdometryExample(unittest.TestCase):
# Check first pose equality # Check first pose equality
pose_1 = result.atPose2(1) pose_1 = result.atPose2(1)
self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -1,11 +1,25 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
PlanarSLAM unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
from math import pi from math import pi
import numpy as np import numpy as np
class TestPose2SLAMExample(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
def test_Pose2SLAMExample(self):
class TestPlanarSLAM(GtsamTestCase):
def test_PlanarSLAM(self):
# Assumptions # Assumptions
# - All values are axis aligned # - All values are axis aligned
# - Robot poses are facing along the X axis (horizontal, to the right in images) # - Robot poses are facing along the X axis (horizontal, to the right in images)
@ -56,7 +70,7 @@ class TestPose2SLAMExample(unittest.TestCase):
P = marginals.marginalCovariance(1) P = marginals.marginalCovariance(1)
pose_1 = result.atPose2(1) pose_1 = result.atPose2(1)
self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4)

View File

@ -1,12 +1,23 @@
"""Pose2 unit tests.""" """
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Pose2 unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import numpy as np import numpy as np
import gtsam
from gtsam import Pose2 from gtsam import Pose2
from gtsam.utils.test_case import GtsamTestCase
class TestPose2(unittest.TestCase): class TestPose2(GtsamTestCase):
"""Test selected Pose2 methods.""" """Test selected Pose2 methods."""
def test_adjoint(self): def test_adjoint(self):

View File

@ -1,9 +1,23 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Pose2SLAM unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
from math import pi from math import pi
import numpy as np import numpy as np
class TestPose2SLAMExample(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestPose2SLAMExample(GtsamTestCase):
def test_Pose2SLAMExample(self): def test_Pose2SLAMExample(self):
# Assumptions # Assumptions
@ -56,7 +70,7 @@ class TestPose2SLAMExample(unittest.TestCase):
P = marginals.marginalCovariance(1) P = marginals.marginalCovariance(1)
pose_1 = result.atPose2(1) pose_1 = result.atPose2(1)
self.assertTrue(pose_1.equals(gtsam.Pose2(), 1e-4)) self.gtsamAssertEquals(pose_1, gtsam.Pose2(), 1e-4)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -1,13 +1,24 @@
"""Pose3 unit tests.""" """
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Pose3 unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import math import math
import unittest import unittest
import numpy as np import numpy as np
import gtsam
from gtsam import Point3, Pose3, Rot3 from gtsam import Point3, Pose3, Rot3
from gtsam.utils.test_case import GtsamTestCase
class TestPose3(unittest.TestCase): class TestPose3(GtsamTestCase):
"""Test selected Pose3 methods.""" """Test selected Pose3 methods."""
def test_between(self): def test_between(self):
@ -16,14 +27,14 @@ class TestPose3(unittest.TestCase):
T3 = Pose3(Rot3.Rodrigues(-90, 0, 0), Point3(1, 2, 3)) T3 = Pose3(Rot3.Rodrigues(-90, 0, 0), Point3(1, 2, 3))
expected = T2.inverse().compose(T3) expected = T2.inverse().compose(T3)
actual = T2.between(T3) actual = T2.between(T3)
self.assertTrue(actual.equals(expected, 1e-6)) self.gtsamAssertEquals(actual, expected, 1e-6)
def test_transform_to(self): def test_transform_to(self):
"""Test transform_to method.""" """Test transform_to method."""
transform = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) transform = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0))
actual = transform.transform_to(Point3(3, 2, 10)) actual = transform.transform_to(Point3(3, 2, 10))
expected = Point3(2, 1, 10) expected = Point3(2, 1, 10)
self.assertTrue(actual.equals(expected, 1e-6)) self.gtsamAssertEquals(actual, expected, 1e-6)
def test_range(self): def test_range(self):
"""Test range method.""" """Test range method."""

View File

@ -1,10 +1,24 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
PoseSLAM unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import numpy as np
import gtsam
from math import pi from math import pi
import numpy as np
import gtsam
from gtsam.utils.test_case import GtsamTestCase
from gtsam.utils.circlePose3 import * from gtsam.utils.circlePose3 import *
class TestPose3SLAMExample(unittest.TestCase):
class TestPose3SLAMExample(GtsamTestCase):
def test_Pose3SLAMExample(self): def test_Pose3SLAMExample(self):
# Create a hexagon of poses # Create a hexagon of poses
@ -40,7 +54,7 @@ class TestPose3SLAMExample(unittest.TestCase):
result = optimizer.optimizeSafely() result = optimizer.optimizeSafely()
pose_1 = result.atPose3(1) pose_1 = result.atPose3(1)
self.assertTrue(pose_1.equals(p1, 1e-4)) self.gtsamAssertEquals(pose_1, p1, 1e-4)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -1,8 +1,22 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
PriorFactor unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
import numpy as np import numpy as np
class TestPriorFactor(unittest.TestCase): import gtsam
from gtsam.utils.test_case import GtsamTestCase
class TestPriorFactor(GtsamTestCase):
def test_PriorFactor(self): def test_PriorFactor(self):
values = gtsam.Values() values = gtsam.Values()

View File

@ -1,11 +1,24 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
SFM unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
from gtsam import symbol
import numpy as np import numpy as np
import gtsam
import gtsam.utils.visual_data_generator as generator import gtsam.utils.visual_data_generator as generator
from gtsam import symbol
from gtsam.utils.test_case import GtsamTestCase
class TestSFMExample(unittest.TestCase): class TestSFMExample(GtsamTestCase):
def test_SFMExample(self): def test_SFMExample(self):
options = generator.Options() options = generator.Options()
@ -59,11 +72,11 @@ class TestSFMExample(unittest.TestCase):
# Check optimized results, should be equal to ground truth # Check optimized results, should be equal to ground truth
for i in range(len(truth.cameras)): for i in range(len(truth.cameras)):
pose_i = result.atPose3(symbol(ord('x'), i)) pose_i = result.atPose3(symbol(ord('x'), i))
self.assertTrue(pose_i.equals(truth.cameras[i].pose(), 1e-5)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5)
for j in range(len(truth.points)): for j in range(len(truth.points)):
point_j = result.atPoint3(symbol(ord('p'), j)) point_j = result.atPoint3(symbol(ord('p'), j))
self.assertTrue(point_j.equals(truth.points[j], 1e-5)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -5,11 +5,9 @@ All Rights Reserved
See LICENSE for the license information See LICENSE for the license information
Unit tests for IMU testing scenarios. Scenario unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python) Author: Frank Dellaert & Duy Nguyen Ta (Python)
""" """
# pylint: disable=invalid-name, E1101
from __future__ import print_function from __future__ import print_function
import math import math
@ -18,9 +16,12 @@ import unittest
import numpy as np import numpy as np
import gtsam import gtsam
from gtsam.utils.test_case import GtsamTestCase
# pylint: disable=invalid-name, E1101
class TestScenario(unittest.TestCase): class TestScenario(GtsamTestCase):
def setUp(self): def setUp(self):
pass pass
@ -44,8 +45,8 @@ class TestScenario(unittest.TestCase):
T30 = scenario.pose(T) T30 = scenario.pose(T)
np.testing.assert_almost_equal( np.testing.assert_almost_equal(
np.array([math.pi, 0, math.pi]), T30.rotation().xyz()) np.array([math.pi, 0, math.pi]), T30.rotation().xyz())
self.assertTrue(gtsam.Point3( self.gtsamAssertEquals(gtsam.Point3(
0, 0, 2.0 * R).equals(T30.translation(), 1e-9)) 0, 0, 2.0 * R), T30.translation(), 1e-9)
if __name__ == '__main__': if __name__ == '__main__':

View File

@ -1,18 +1,31 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
SimpleCamera unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import math import math
import numpy as np
import unittest import unittest
from gtsam import Pose2, Point3, Rot3, Pose3, Cal3_S2, SimpleCamera import numpy as np
import gtsam
from gtsam import Cal3_S2, Point3, Pose2, Pose3, Rot3, SimpleCamera
from gtsam.utils.test_case import GtsamTestCase
K = Cal3_S2(625, 625, 0, 0, 0) K = Cal3_S2(625, 625, 0, 0, 0)
class TestSimpleCamera(unittest.TestCase): class TestSimpleCamera(GtsamTestCase):
def test_constructor(self): def test_constructor(self):
pose1 = Pose3(Rot3(np.diag([1, -1, -1])), Point3(0, 0, 0.5)) pose1 = Pose3(Rot3(np.diag([1, -1, -1])), Point3(0, 0, 0.5))
camera = SimpleCamera(pose1, K) camera = SimpleCamera(pose1, K)
self.assertTrue(camera.calibration().equals(K, 1e-9)) self.gtsamAssertEquals(camera.calibration(), K, 1e-9)
self.assertTrue(camera.pose().equals(pose1, 1e-9)) self.gtsamAssertEquals(camera.pose(), pose1, 1e-9)
def test_level2(self): def test_level2(self):
# Create a level camera, looking in Y-direction # Create a level camera, looking in Y-direction
@ -25,7 +38,7 @@ class TestSimpleCamera(unittest.TestCase):
z = Point3(0,1,0) z = Point3(0,1,0)
wRc = Rot3(x,y,z) wRc = Rot3(x,y,z)
expected = Pose3(wRc,Point3(0.4,0.3,0.1)) expected = Pose3(wRc,Point3(0.4,0.3,0.1))
self.assertTrue(camera.pose().equals(expected, 1e-9)) self.gtsamAssertEquals(camera.pose(), expected, 1e-9)
if __name__ == "__main__": if __name__ == "__main__":

View File

@ -1,10 +1,23 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Stereo VO unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import gtsam
from gtsam import symbol
import numpy as np import numpy as np
import gtsam
from gtsam import symbol
from gtsam.utils.test_case import GtsamTestCase
class TestStereoVOExample(unittest.TestCase):
class TestStereoVOExample(GtsamTestCase):
def test_StereoVOExample(self): def test_StereoVOExample(self):
## Assumptions ## Assumptions
@ -60,10 +73,10 @@ class TestStereoVOExample(unittest.TestCase):
## check equality for the first pose and point ## check equality for the first pose and point
pose_x1 = result.atPose3(x1) pose_x1 = result.atPose3(x1)
self.assertTrue(pose_x1.equals(first_pose,1e-4)) self.gtsamAssertEquals(pose_x1, first_pose,1e-4)
point_l1 = result.atPoint3(l1) point_l1 = result.atPoint3(l1)
self.assertTrue(point_l1.equals(expected_l1,1e-4)) self.gtsamAssertEquals(point_l1, expected_l1,1e-4)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -5,7 +5,7 @@ All Rights Reserved
See LICENSE for the license information See LICENSE for the license information
Unit tests for IMU testing scenarios. Values unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python) Author: Frank Dellaert & Duy Nguyen Ta (Python)
""" """
# pylint: disable=invalid-name, E1101, E0611 # pylint: disable=invalid-name, E1101, E0611
@ -13,12 +13,14 @@ import unittest
import numpy as np import numpy as np
import gtsam
from gtsam import (Cal3_S2, Cal3Bundler, Cal3DS2, EssentialMatrix, Point2, from gtsam import (Cal3_S2, Cal3Bundler, Cal3DS2, EssentialMatrix, Point2,
Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values, Point3, Pose2, Pose3, Rot2, Rot3, Unit3, Values,
imuBias_ConstantBias) imuBias_ConstantBias)
from gtsam.utils.test_case import GtsamTestCase
class TestValues(unittest.TestCase): class TestValues(GtsamTestCase):
def test_values(self): def test_values(self):
values = Values() values = Values()
@ -58,26 +60,26 @@ class TestValues(unittest.TestCase):
mat2 = np.array([[1, 2, ], [3, 5]]) mat2 = np.array([[1, 2, ], [3, 5]])
values.insert(13, mat2) values.insert(13, mat2)
self.assertTrue(values.atPoint2(0).equals(Point2(0,0), tol)) self.gtsamAssertEquals(values.atPoint2(0), Point2(0,0), tol)
self.assertTrue(values.atPoint3(1).equals(Point3(0,0,0), tol)) self.gtsamAssertEquals(values.atPoint3(1), Point3(0,0,0), tol)
self.assertTrue(values.atRot2(2).equals(Rot2(), tol)) self.gtsamAssertEquals(values.atRot2(2), Rot2(), tol)
self.assertTrue(values.atPose2(3).equals(Pose2(), tol)) self.gtsamAssertEquals(values.atPose2(3), Pose2(), tol)
self.assertTrue(values.atRot3(4).equals(Rot3(), tol)) self.gtsamAssertEquals(values.atRot3(4), Rot3(), tol)
self.assertTrue(values.atPose3(5).equals(Pose3(), tol)) self.gtsamAssertEquals(values.atPose3(5), Pose3(), tol)
self.assertTrue(values.atCal3_S2(6).equals(Cal3_S2(), tol)) self.gtsamAssertEquals(values.atCal3_S2(6), Cal3_S2(), tol)
self.assertTrue(values.atCal3DS2(7).equals(Cal3DS2(), tol)) self.gtsamAssertEquals(values.atCal3DS2(7), Cal3DS2(), tol)
self.assertTrue(values.atCal3Bundler(8).equals(Cal3Bundler(), tol)) self.gtsamAssertEquals(values.atCal3Bundler(8), Cal3Bundler(), tol)
self.assertTrue(values.atEssentialMatrix(9).equals(E, tol)) self.gtsamAssertEquals(values.atEssentialMatrix(9), E, tol)
self.assertTrue(values.atimuBias_ConstantBias( self.gtsamAssertEquals(values.atimuBias_ConstantBias(
10).equals(imuBias_ConstantBias(), tol)) 10), imuBias_ConstantBias(), tol)
# special cases for Vector and Matrix: # special cases for Vector and Matrix:
actualVector = values.atVector(11) actualVector = values.atVector(11)
self.assertTrue(np.allclose(vec, actualVector, tol)) np.testing.assert_allclose(vec, actualVector, tol)
actualMatrix = values.atMatrix(12) actualMatrix = values.atMatrix(12)
self.assertTrue(np.allclose(mat, actualMatrix, tol)) np.testing.assert_allclose(mat, actualMatrix, tol)
actualMatrix2 = values.atMatrix(13) actualMatrix2 = values.atMatrix(13)
self.assertTrue(np.allclose(mat2, actualMatrix2, tol)) np.testing.assert_allclose(mat2, actualMatrix2, tol)
if __name__ == "__main__": if __name__ == "__main__":

View File

@ -1,10 +1,25 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
visual_isam unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import numpy as np import numpy as np
from gtsam import symbol
import gtsam
import gtsam.utils.visual_data_generator as generator import gtsam.utils.visual_data_generator as generator
import gtsam.utils.visual_isam as visual_isam import gtsam.utils.visual_isam as visual_isam
from gtsam import symbol
from gtsam.utils.test_case import GtsamTestCase
class TestVisualISAMExample(unittest.TestCase):
class TestVisualISAMExample(GtsamTestCase):
def test_VisualISAMExample(self): def test_VisualISAMExample(self):
# Data Options # Data Options
@ -32,11 +47,11 @@ class TestVisualISAMExample(unittest.TestCase):
for i in range(len(truth.cameras)): for i in range(len(truth.cameras)):
pose_i = result.atPose3(symbol(ord('x'), i)) pose_i = result.atPose3(symbol(ord('x'), i))
self.assertTrue(pose_i.equals(truth.cameras[i].pose(), 1e-5)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5)
for j in range(len(truth.points)): for j in range(len(truth.points)):
point_j = result.atPoint3(symbol(ord('l'), j)) point_j = result.atPoint3(symbol(ord('l'), j))
self.assertTrue(point_j.equals(truth.points[j], 1e-5)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5)
if __name__ == "__main__": if __name__ == "__main__":
unittest.main() unittest.main()

View File

@ -6,7 +6,7 @@ All Rights Reserved
See LICENSE for the license information See LICENSE for the license information
Unit tests for testing dataset access. Unit tests for testing dataset access.
Author: Frank Dellaert Author: Frank Dellaert & Duy Nguyen Ta (Python)
""" """
# pylint: disable=invalid-name, no-name-in-module, no-member # pylint: disable=invalid-name, no-name-in-module, no-member
@ -16,9 +16,10 @@ import unittest
import gtsam import gtsam
from gtsam import BetweenFactorPose3, BetweenFactorPose3s from gtsam import BetweenFactorPose3, BetweenFactorPose3s
from gtsam.utils.test_case import GtsamTestCase
class TestDataset(unittest.TestCase): class TestDataset(GtsamTestCase):
"""Tests for datasets.h wrapper.""" """Tests for datasets.h wrapper."""
def setUp(self): def setUp(self):

View File

@ -15,11 +15,12 @@ import numpy as np
import gtsam import gtsam
from gtsam import NonlinearFactorGraph, Point3, Pose3, Rot3, Values from gtsam import NonlinearFactorGraph, Point3, Pose3, Rot3, Values
from gtsam.utils.test_case import GtsamTestCase
x0, x1, x2, x3 = 0, 1, 2, 3 x0, x1, x2, x3 = 0, 1, 2, 3
class TestValues(unittest.TestCase): class TestValues(GtsamTestCase):
def setUp(self): def setUp(self):
@ -67,10 +68,10 @@ class TestValues(unittest.TestCase):
initial = gtsam.InitializePose3.computeOrientationsChordal(pose3Graph) initial = gtsam.InitializePose3.computeOrientationsChordal(pose3Graph)
# comparison is up to M_PI, that's why we add some multiples of 2*M_PI # comparison is up to M_PI, that's why we add some multiples of 2*M_PI
self.assertTrue(initial.atRot3(x0).equals(self.R0, 1e-6)) self.gtsamAssertEquals(initial.atRot3(x0), self.R0, 1e-6)
self.assertTrue(initial.atRot3(x1).equals(self.R1, 1e-6)) self.gtsamAssertEquals(initial.atRot3(x1), self.R1, 1e-6)
self.assertTrue(initial.atRot3(x2).equals(self.R2, 1e-6)) self.gtsamAssertEquals(initial.atRot3(x2), self.R2, 1e-6)
self.assertTrue(initial.atRot3(x3).equals(self.R3, 1e-6)) self.gtsamAssertEquals(initial.atRot3(x3), self.R3, 1e-6)
def test_initializePoses(self): def test_initializePoses(self):
g2oFile = gtsam.findExampleDataFile("pose3example-grid") g2oFile = gtsam.findExampleDataFile("pose3example-grid")
@ -81,7 +82,7 @@ class TestValues(unittest.TestCase):
initial = gtsam.InitializePose3.initialize(inputGraph) initial = gtsam.InitializePose3.initialize(inputGraph)
# TODO(frank): very loose !! # TODO(frank): very loose !!
self.assertTrue(initial.equals(expectedValues, 0.1)) self.gtsamAssertEquals(initial, expectedValues, 0.1)
if __name__ == "__main__": if __name__ == "__main__":

View File

@ -1,7 +1,20 @@
"""
GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved
See LICENSE for the license information
Cal3Unified unit tests.
Author: Frank Dellaert & Duy Nguyen Ta (Python)
"""
import unittest import unittest
import numpy as np
import gtsam import gtsam
import gtsam_unstable import gtsam_unstable
import numpy as np from gtsam.utils.test_case import GtsamTestCase
def _timestamp_key_value(key, value): def _timestamp_key_value(key, value):
@ -10,7 +23,7 @@ def _timestamp_key_value(key, value):
) )
class TestFixedLagSmootherExample(unittest.TestCase): class TestFixedLagSmootherExample(GtsamTestCase):
''' '''
Tests the fixed lag smoother wrapper Tests the fixed lag smoother wrapper
''' '''