Skip to content

Commit

Permalink
update python wrapper
Browse files Browse the repository at this point in the history
  • Loading branch information
gchenfc committed Nov 11, 2021
1 parent 508db60 commit d86fc98
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 1 deletion.
3 changes: 3 additions & 0 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
10 changes: 9 additions & 1 deletion python/gtsam/tests/test_Pose3.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,16 @@ def test_range(self):
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)
Expand Down

0 comments on commit d86fc98

Please sign in to comment.