Fixed static issue
parent
37ed46cee1
commit
7138236f71
|
@ -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)
|
||||
|
||||
|
||||
|
|
4
gtsam.h
4
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
|
||||
|
|
Loading…
Reference in New Issue