From 936a7ac073cfa3c74e89c73eb3612591dc6a564f Mon Sep 17 00:00:00 2001 From: yotams Date: Wed, 6 Apr 2022 09:27:57 +0300 Subject: [PATCH] added test for the wrapper --- .../tests/test_ProjectionFactorRollingShutter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/python/gtsam_unstable/tests/test_ProjectionFactorRollingShutter.py b/python/gtsam_unstable/tests/test_ProjectionFactorRollingShutter.py index 23a9d0831..0e4db3faf 100644 --- a/python/gtsam_unstable/tests/test_ProjectionFactorRollingShutter.py +++ b/python/gtsam_unstable/tests/test_ProjectionFactorRollingShutter.py @@ -27,7 +27,7 @@ point_noise = gtsam.noiseModel.Diagonal.Sigmas(np.ones(2)) cal = gtsam.Cal3_S2() body_p_sensor = gtsam.Pose3() alpha = 0.1 -measured = array([0.13257015, 0.0004157]) +measured = np.array([0.13257015, 0.0004157]) class TestProjectionFactorRollingShutter(GtsamTestCase): @@ -52,7 +52,7 @@ class TestProjectionFactorRollingShutter(GtsamTestCase): values.insert(1, pose2) values.insert(2, point) factor = gtsam_unstable.ProjectionFactorRollingShutter(measured, alpha, point_noise, 0, 1, 2, cal) - self.assertEqual(factor.error(values), 0) + self.gtsamAssertEquals(factor.error(values), np.array(0), tol=1e-9) if __name__ == '__main__':