Skip to content

Commit

Permalink
Merge pull request #1302 from borglab/wrap-unit3-rot
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal authored Dec 25, 2022
2 parents d7491a1 + 3a2816e commit af6a4f2
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 1 deletion.
4 changes: 4 additions & 0 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -340,6 +340,10 @@ class Rot3 {
gtsam::Point3 rotate(const gtsam::Point3& p) const;
gtsam::Point3 unrotate(const gtsam::Point3& p) const;

// Group action on Unit3
gtsam::Unit3 rotate(const gtsam::Unit3& p) const;
gtsam::Unit3 unrotate(const gtsam::Unit3& p) const;

// Standard Interface
static gtsam::Rot3 Expmap(Vector v);
static Vector Logmap(const gtsam::Rot3& p);
Expand Down
27 changes: 26 additions & 1 deletion python/gtsam/tests/test_Rot3.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import numpy as np

import gtsam
from gtsam import Rot3
from gtsam import Point3, Rot3, Unit3
from gtsam.utils.test_case import GtsamTestCase


Expand Down Expand Up @@ -2032,6 +2032,31 @@ def test_axis_angle_stress_test(self) -> None:
angle_deg = np.rad2deg(angle)
assert angle_deg < 180

def test_rotate(self) -> None:
"""Test that rotate() works for both Point3 and Unit3."""
R = Rot3(np.array([[1, 0, 0], [0, -1, 0], [0, 0, 1]]))
p = Point3(1., 1., 1.)
u = Unit3(np.array([1, 1, 1]))
actual_p = R.rotate(p)
actual_u = R.rotate(u)
expected_p = Point3(np.array([1, -1, 1]))
expected_u = Unit3(np.array([1, -1, 1]))
np.testing.assert_array_equal(actual_p, expected_p)
np.testing.assert_array_equal(actual_u.point3(), expected_u.point3())

def test_unrotate(self) -> None:
"""Test that unrotate() after rotate() yields original Point3/Unit3."""
wRc = Rot3(np.array(R1_R2_pairs[0][0]))
c_p = Point3(1., 1., 1.)
c_u = Unit3(np.array([1, 1, 1]))
w_p = wRc.rotate(c_p)
w_u = wRc.rotate(c_u)
actual_p = wRc.unrotate(w_p)
actual_u = wRc.unrotate(w_u)

np.testing.assert_almost_equal(actual_p, c_p, decimal=6)
np.testing.assert_almost_equal(actual_u.point3(), c_u.point3(), decimal=6)


if __name__ == "__main__":
unittest.main()

0 comments on commit af6a4f2

Please sign in to comment.