diff --git a/python/gtsam/tests/test_Rot3.py b/python/gtsam/tests/test_Rot3.py index e1eeb7fe4f..74a131b07a 100644 --- a/python/gtsam/tests/test_Rot3.py +++ b/python/gtsam/tests/test_Rot3.py @@ -2034,13 +2034,13 @@ def test_axis_angle_stress_test(self) -> None: def test_rotate(self) -> None: """Test that rotate() works for both Point3 and Unit3.""" - R = Rot3(np.array([[1, 0, 0], [0, -1, 0], [0, 0, 1]])) + R = Rot3(np.array([[1, 0, 0], [0, -1, 0], [0, 0, -1]])) p = Point3(1., 1., 1.) u = Unit3(np.array([1, 1, 1])) actual_p = R.rotate(p) actual_u = R.rotate(u) - expected_p = Point3(np.array([1, -1, 1])) - expected_u = Unit3(np.array([1, -1, 1])) + expected_p = Point3(np.array([1, -1, -1])) + expected_u = Unit3(np.array([1, -1, -1])) np.testing.assert_array_equal(actual_p, expected_p) np.testing.assert_array_equal(actual_u.point3(), expected_u.point3())