Skip to content

Commit 8c6d422

Browse files
authored
Add methods to convert SE3 to/from the rvec, tvec format used by OpenCV (#157)
1 parent 59873f1 commit 8c6d422

File tree

2 files changed

+45
-1
lines changed

2 files changed

+45
-1
lines changed

spatialmath/pose3d.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1315,6 +1315,21 @@ def delta(self, X2: Optional[SE3] = None) -> R6:
13151315
else:
13161316
return smb.tr2delta(self.A, X2.A)
13171317

1318+
def rtvec(self) -> Tuple[R3, R3]:
1319+
"""
1320+
Convert to OpenCV-style rotation and translation vectors
1321+
1322+
:return: rotation and translation vectors
1323+
:rtype: ndarray(3), ndarray(3)
1324+
1325+
Many OpenCV functions accept pose as two 3-vectors: a rotation vector using
1326+
exponential coordinates and a translation vector. This method combines them
1327+
into an SE(3) instance.
1328+
1329+
:seealso: :meth:`rtvec`
1330+
"""
1331+
return SO3(self).log(twist=True), self.t
1332+
13181333
def Ad(self) -> R6x6:
13191334
r"""
13201335
Adjoint of SE(3)
@@ -1856,6 +1871,26 @@ def Exp(cls, S: Union[R6, R4x4], check: bool = True) -> SE3:
18561871
else:
18571872
return cls(smb.trexp(S), check=False)
18581873

1874+
@classmethod
1875+
def RTvec(cls, rvec: ArrayLike3, tvec: ArrayLike3) -> Self:
1876+
"""
1877+
Construct a new SE(3) from OpenCV-style rotation and translation vectors
1878+
1879+
:param rvec: rotation as exponential coordinates
1880+
:type rvec: ArrayLike3
1881+
:param tvec: translation vector
1882+
:type tvec: ArrayLike3
1883+
:return: An SE(3) instance
1884+
:rtype: SE3 instance
1885+
1886+
Many OpenCV functions (such as pose estimation) return pose as two 3-vectors: a
1887+
rotation vector using exponential coordinates and a translation vector. This
1888+
method combines them into an SE(3) instance.
1889+
1890+
:seealso: :meth:`rtvec`
1891+
"""
1892+
return SE3.Rt(smb.trexp(rvec), tvec)
1893+
18591894
@classmethod
18601895
def Delta(cls, d: ArrayLike6) -> SE3:
18611896
r"""

tests/test_pose3d.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,6 @@ def test_conversion(self):
254254
nt.assert_array_almost_equal(q.SO3(), R_from_q)
255255
nt.assert_array_almost_equal(q.SO3().UnitQuaternion(), q)
256256

257-
258257
def test_shape(self):
259258
a = SO3()
260259
self.assertEqual(a._A.shape, a.shape)
@@ -1370,6 +1369,16 @@ def test_functions_vect(self):
13701369
# .T
13711370
pass
13721371

1372+
def test_rtvec(self):
1373+
# OpenCV compatibility functions
1374+
T = SE3.RTvec([0, 1, 0], [2, 3, 4])
1375+
nt.assert_equal(T.t, [2, 3, 4])
1376+
nt.assert_equal(T.R, SO3.Ry(1))
1377+
1378+
rvec, tvec = T.rtvec()
1379+
nt.assert_equal(rvec, [0, 1, 0])
1380+
nt.assert_equal(tvec, [2, 3, 4])
1381+
13731382

13741383
# ---------------------------------------------------------------------------------------#
13751384
if __name__ == "__main__":

0 commit comments

Comments
 (0)