diff --git a/cython/gtsam/tests/test_Pose2.py b/cython/gtsam/tests/test_Pose2.py index f43ec0683..afd0c5773 100644 --- a/cython/gtsam/tests/test_Pose2.py +++ b/cython/gtsam/tests/test_Pose2.py @@ -12,8 +12,8 @@ class TestPose2(unittest.TestCase): def test_adjoint(self): """Test adjoint method.""" xi = np.array([1, 2, 3]) - expected = np.dot(Pose2.adjointMap(xi), xi) - actual = Pose2.adjoint(xi, xi) + expected = np.dot(Pose2.adjointMap_(xi), xi) + actual = Pose2.adjoint_(xi, xi) np.testing.assert_array_equal(actual, expected) diff --git a/gtsam.h b/gtsam.h index 4720d9d6b..48768db40 100644 --- a/gtsam.h +++ b/gtsam.h @@ -578,8 +578,8 @@ class Pose2 { Matrix AdjointMap() const; Vector Adjoint(Vector xi) const; static Matrix adjointMap_(Vector v); - Vector adjoint_(Vector xi, Vector y); - Vector adjointTranspose(Vector xi, Vector y); + static Vector adjoint_(Vector xi, Vector y); + static Vector adjointTranspose(Vector xi, Vector y); static Matrix wedge(double vx, double vy, double w); // Group Actions on Point2