Fixed static issue

release/4.3a0
Frank Dellaert 2019-02-11 10:52:36 -05:00
parent 37ed46cee1
commit 7138236f71
2 changed files with 4 additions and 4 deletions

View File

@ -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)

View File

@ -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