Skip to content

Commit 628ffb1

Browse files
committed
Matrix versions for Pose2 group action
1 parent 56b83af commit 628ffb1

File tree

5 files changed

+69
-4
lines changed

5 files changed

+69
-4
lines changed

gtsam/geometry/Pose2.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -213,6 +213,14 @@ Point2 Pose2::transformTo(const Point2& point,
213213
return q;
214214
}
215215

216+
Matrix Pose2::transformTo(const Matrix& points) const {
217+
if (points.rows() != 2) {
218+
throw std::invalid_argument("Pose2:transformTo expects 2*N matrix.");
219+
}
220+
const Matrix2 Rt = rotation().transpose();
221+
return Rt * (points.colwise() - t_); // Eigen broadcasting!
222+
}
223+
216224
/* ************************************************************************* */
217225
// see doc/math.lyx, SE(2) section
218226
Point2 Pose2::transformFrom(const Point2& point,
@@ -224,6 +232,15 @@ Point2 Pose2::transformFrom(const Point2& point,
224232
return q + t_;
225233
}
226234

235+
236+
Matrix Pose2::transformFrom(const Matrix& points) const {
237+
if (points.rows() != 2) {
238+
throw std::invalid_argument("Pose2:transformFrom expects 2*N matrix.");
239+
}
240+
const Matrix2 R = rotation().matrix();
241+
return (R * points).colwise() + t_; // Eigen broadcasting!
242+
}
243+
227244
/* ************************************************************************* */
228245
Rot2 Pose2::bearing(const Point2& point,
229246
OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 2> Hpoint) const {

gtsam/geometry/Pose2.h

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -199,13 +199,29 @@ class Pose2: public LieGroup<Pose2, 3> {
199199
OptionalJacobian<2, 3> Dpose = boost::none,
200200
OptionalJacobian<2, 2> Dpoint = boost::none) const;
201201

202+
/**
203+
* @brief transform many points in world coordinates and transform to Pose.
204+
* @param points 2*N matrix in world coordinates
205+
* @return points in Pose coordinates, as 2*N Matrix
206+
*/
207+
Matrix transformTo(const Matrix& points) const;
208+
202209
/** Return point coordinates in global frame */
203210
GTSAM_EXPORT Point2 transformFrom(const Point2& point,
204211
OptionalJacobian<2, 3> Dpose = boost::none,
205212
OptionalJacobian<2, 2> Dpoint = boost::none) const;
206213

214+
/**
215+
* @brief transform many points in Pose coordinates and transform to world.
216+
* @param points 2*N matrix in Pose coordinates
217+
* @return points in world coordinates, as 2*N Matrix
218+
*/
219+
Matrix transformFrom(const Matrix& points) const;
220+
207221
/** syntactic sugar for transformFrom */
208-
inline Point2 operator*(const Point2& point) const { return transformFrom(point);}
222+
inline Point2 operator*(const Point2& point) const {
223+
return transformFrom(point);
224+
}
209225

210226
/// @}
211227
/// @name Standard Interface

gtsam/geometry/geometry.i

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -406,6 +406,10 @@ class Pose2 {
406406
gtsam::Point2 transformFrom(const gtsam::Point2& p) const;
407407
gtsam::Point2 transformTo(const gtsam::Point2& p) const;
408408

409+
// Matrix versions
410+
Matrix transformFrom(const Matrix& points) const;
411+
Matrix transformTo(const Matrix& points) const;
412+
409413
// Standard Interface
410414
double x() const;
411415
double y() const;

python/gtsam/tests/test_Pose2.py

Lines changed: 30 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,11 @@
88
Pose2 unit tests.
99
Author: Frank Dellaert & Duy Nguyen Ta & John Lambert
1010
"""
11+
import math
1112
import unittest
1213

13-
import numpy as np
14-
1514
import gtsam
15+
import numpy as np
1616
from gtsam import Point2, Point2Pairs, Pose2
1717
from gtsam.utils.test_case import GtsamTestCase
1818

@@ -26,6 +26,34 @@ def test_adjoint(self) -> None:
2626
actual = Pose2.adjoint_(xi, xi)
2727
np.testing.assert_array_equal(actual, expected)
2828

29+
def test_transformTo(self):
30+
"""Test transformTo method."""
31+
pose = Pose2(2, 4, -math.pi/2)
32+
actual = pose.transformTo(Point2(3, 2))
33+
expected = Point2(2, 1)
34+
self.gtsamAssertEquals(actual, expected, 1e-6)
35+
36+
# multi-point version
37+
points = np.stack([Point2(3, 2), Point2(3, 2)]).T
38+
actual_array = pose.transformTo(points)
39+
self.assertEqual(actual_array.shape, (2, 2))
40+
expected_array = np.stack([expected, expected]).T
41+
np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
42+
43+
def test_transformFrom(self):
44+
"""Test transformFrom method."""
45+
pose = Pose2(2, 4, -math.pi/2)
46+
actual = pose.transformFrom(Point2(2, 1))
47+
expected = Point2(3, 2)
48+
self.gtsamAssertEquals(actual, expected, 1e-6)
49+
50+
# multi-point version
51+
points = np.stack([Point2(2, 1), Point2(2, 1)]).T
52+
actual_array = pose.transformFrom(points)
53+
self.assertEqual(actual_array.shape, (2, 2))
54+
expected_array = np.stack([expected, expected]).T
55+
np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
56+
2957
def test_align(self) -> None:
3058
"""Ensure estimation of the Pose2 element to align two 2d point clouds succeeds.
3159

python/gtsam/tests/test_Pose3.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ def test_transformTo(self):
4545
np.testing.assert_allclose(actual_array, expected_array, atol=1e-6)
4646

4747
def test_transformFrom(self):
48-
"""Test transformTo method."""
48+
"""Test transformFrom method."""
4949
pose = Pose3(Rot3.Rodrigues(0, 0, -math.pi/2), Point3(2, 4, 0))
5050
actual = pose.transformFrom(Point3(2, 1, 10))
5151
expected = Point3(3, 2, 10)

0 commit comments

Comments
 (0)