Skip to content

Commit 94811c9

Browse files
committed
Add methods to convert SE3 to/from the rvec, tvec format used for poses within OpenCV
1 parent 0ff5c83 commit 94811c9

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
@@ -1292,6 +1292,21 @@ def delta(self, X2: Optional[SE3] = None) -> R6:
12921292
else:
12931293
return smb.tr2delta(self.A, X2.A)
12941294

1295+
def rtvec(self) -> Tuple[R3, R3]:
1296+
"""
1297+
Convert to OpenCV-style rotation and translation vectors
1298+
1299+
:return: rotation and translation vectors
1300+
:rtype: ndarray(3), ndarray(3)
1301+
1302+
Many OpenCV functions accept pose as two 3-vectors: a rotation vector using
1303+
exponential coordinates and a translation vector. This method combines them
1304+
into an SE(3) instance.
1305+
1306+
:seealso: :meth:`rtvec`
1307+
"""
1308+
return SO3(self).log(twist=True), self.t
1309+
12951310
def Ad(self) -> R6x6:
12961311
r"""
12971312
Adjoint of SE(3)
@@ -1833,6 +1848,26 @@ def Exp(cls, S: Union[R6, R4x4], check: bool = True) -> SE3:
18331848
else:
18341849
return cls(smb.trexp(S), check=False)
18351850

1851+
@classmethod
1852+
def RTvec(cls, rvec: ArrayLike3, tvec: ArrayLike3) -> Self:
1853+
"""
1854+
Construct a new SE(3) from OpenCV-style rotation and translation vectors
1855+
1856+
:param rvec: rotation as exponential coordinates
1857+
:type rvec: ArrayLike3
1858+
:param tvec: translation vector
1859+
:type tvec: ArrayLike3
1860+
:return: An SE(3) instance
1861+
:rtype: SE3 instance
1862+
1863+
Many OpenCV functions (such as pose estimation) return pose as two 3-vectors: a
1864+
rotation vector using exponential coordinates and a translation vector. This
1865+
method combines them into an SE(3) instance.
1866+
1867+
:seealso: :meth:`rtvec`
1868+
"""
1869+
return SE3.Rt(smb.trexp(rvec), tvec)
1870+
18361871
@classmethod
18371872
def Delta(cls, d: ArrayLike6) -> SE3:
18381873
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)
@@ -1339,6 +1338,16 @@ def test_functions_vect(self):
13391338
# .T
13401339
pass
13411340

1341+
def test_rtvec(self):
1342+
# OpenCV compatibility functions
1343+
T = SE3.RTvec([0, 1, 0], [2, 3, 4])
1344+
nt.assert_equal(T.t, [2, 3, 4])
1345+
nt.assert_equal(T.R, SO3.Ry(1))
1346+
1347+
rvec, tvec = T.rtvec()
1348+
nt.assert_equal(rvec, [0, 1, 0])
1349+
nt.assert_equal(tvec, [2, 3, 4])
1350+
13421351

13431352
# ---------------------------------------------------------------------------------------#
13441353
if __name__ == "__main__":

0 commit comments

Comments
 (0)