update python wrapper
parent
508db60f74
commit
d86fc98706
|
|
@ -473,6 +473,9 @@ class Pose3 {
|
|||
Vector logmap(const gtsam::Pose3& pose);
|
||||
Matrix AdjointMap() const;
|
||||
Vector Adjoint(Vector xi) const;
|
||||
Vector AdjointTranspose(Vector xi) const;
|
||||
static Matrix adjointMap(Vector xi);
|
||||
static Vector adjoint(Vector xi, Vector y);
|
||||
static Matrix adjointMap_(Vector xi);
|
||||
static Vector adjoint_(Vector xi, Vector y);
|
||||
static Vector adjointTranspose(Vector xi, Vector y);
|
||||
|
|
|
|||
|
|
@ -59,8 +59,16 @@ class TestPose3(GtsamTestCase):
|
|||
self.assertEqual(math.sqrt(2.0), x1.range(pose=xl2))
|
||||
|
||||
def test_adjoint(self):
|
||||
"""Test adjoint method."""
|
||||
"""Test adjoint methods."""
|
||||
T = Pose3()
|
||||
xi = np.array([1, 2, 3, 4, 5, 6])
|
||||
# test calling functions
|
||||
T.AdjointMap()
|
||||
T.Adjoint(xi)
|
||||
T.AdjointTranspose(xi)
|
||||
Pose3.adjointMap(xi)
|
||||
Pose3.adjoint(xi, xi)
|
||||
# test correctness of adjoint(x, y)
|
||||
expected = np.dot(Pose3.adjointMap_(xi), xi)
|
||||
actual = Pose3.adjoint_(xi, xi)
|
||||
np.testing.assert_array_equal(actual, expected)
|
||||
|
|
|
|||
Loading…
Reference in New Issue