Skip to content

Commit 6ba8539

Browse files
committed
add method to return Euler vector/exponential coords
1 parent 9b8296a commit 6ba8539

1 file changed

Lines changed: 29 additions & 0 deletions

File tree

spatialmath/pose3d.py

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -310,6 +310,34 @@ def angvec(self, unit: str = "rad") -> Tuple[float, R3]:
310310
"""
311311
return smb.tr2angvec(self.R, unit=unit)
312312

313+
def eulervec(self) -> R3:
314+
r"""
315+
SO(3) or SE(3) as Euler vector (exponential coordinates)
316+
317+
:return: :math:`\theta \hat{\bf v}`
318+
:rtype: ndarray(3)
319+
320+
``x.eulervec()`` is the Euler vector (or exponential coordinates) which
321+
is related to angle-axis notation and is the product of the rotation
322+
angle and the rotation axis.
323+
324+
Example:
325+
326+
.. runblock:: pycon
327+
328+
>>> from spatialmath import SO3
329+
>>> R = SO3.Rx(0.3)
330+
>>> R.eulervec()
331+
332+
.. note::
333+
334+
- If the input is SE(3) the translation component is ignored.
335+
336+
:seealso: :meth:`angvec` :func:`~angvec2r`
337+
"""
338+
theta, v = smb.tr2angvec(self.R)
339+
return theta * v
340+
313341
# ------------------------------------------------------------------------ #
314342

315343
@staticmethod
@@ -763,6 +791,7 @@ def Exp(
763791
:param S: Lie algebra so(3)
764792
:type S: ndarray(3,3), ndarray(n,3)
765793
:param check: check that passed matrix is valid so(3), default True
794+
:bool check: bool, optional
766795
:param so3: the input is interpretted as an so(3) matrix not a stack of three twists, default True
767796
:return: SO(3) rotation
768797
:rtype: SO3 instance

0 commit comments

Comments
 (0)