Skip to content

Navigation Menu

Sign in
Appearance settings

Search code, repositories, users, issues, pull requests...

Provide feedback

We read every piece of feedback, and take your input very seriously.

Saved searches

Use saved searches to filter your results more quickly

Appearance settings

Commit 3a8cb03

Browse filesBrowse files
authored
Created internal quaternion conversion function for SO3 (bdaiinstitute#119)
1 parent b16b34f commit 3a8cb03
Copy full SHA for 3a8cb03

File tree

Expand file treeCollapse file tree

2 files changed

+41
-1
lines changed
Filter options
Expand file treeCollapse file tree

2 files changed

+41
-1
lines changed

‎spatialmath/pose3d.py

Copy file name to clipboardExpand all lines: spatialmath/pose3d.py
+26Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,9 @@
3434

3535
from spatialmath.twist import Twist3
3636

37+
from typing import TYPE_CHECKING
38+
if TYPE_CHECKING:
39+
from spatialmath.quaternion import UnitQuaternion
3740

3841
# ============================== SO3 =====================================#
3942

@@ -834,6 +837,29 @@ def Exp(
834837
else:
835838
return cls(smb.trexp(cast(R3, S), check=check), check=False)
836839

840+
def UnitQuaternion(self) -> UnitQuaternion:
841+
"""
842+
SO3 as a unit quaternion instance
843+
844+
:return: a unit quaternion representation
845+
:rtype: UnitQuaternion instance
846+
847+
``R.UnitQuaternion()`` is an ``UnitQuaternion`` instance representing the same rotation
848+
as the SO3 rotation ``R``.
849+
850+
Example:
851+
852+
.. runblock:: pycon
853+
854+
>>> from spatialmath import SO3
855+
>>> SO3.Rz(0.3).UnitQuaternion()
856+
857+
"""
858+
# Function level import to avoid circular dependencies
859+
from spatialmath import UnitQuaternion
860+
861+
return UnitQuaternion(smb.r2q(self.R), check=False)
862+
837863
def angdist(self, other: SO3, metric: int = 6) -> Union[float, ndarray]:
838864
r"""
839865
Angular distance metric between rotations

‎tests/test_pose3d.py

Copy file name to clipboardExpand all lines: tests/test_pose3d.py
+15-1Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
we will assume that the primitives rotx,trotx, etc. all work
99
"""
1010
from math import pi
11-
from spatialmath import SE3, SO3, SE2
11+
from spatialmath import SE3, SO3, SE2, UnitQuaternion
1212
import numpy as np
1313
from spatialmath.base import *
1414
from spatialmath.baseposematrix import BasePoseMatrix
@@ -233,6 +233,20 @@ def test_constructor_TwoVec(self):
233233
# x axis should equal normalized x vector
234234
nt.assert_almost_equal(R.R[:, 0], v3 / np.linalg.norm(v3), 5)
235235

236+
def test_conversion(self):
237+
R = SO3.AngleAxis(0.7, [1,2,3])
238+
q = UnitQuaternion([11,7,3,-6])
239+
240+
R_from_q = SO3(q.R)
241+
q_from_R = UnitQuaternion(R)
242+
243+
nt.assert_array_almost_equal(R.UnitQuaternion(), q_from_R)
244+
nt.assert_array_almost_equal(R.UnitQuaternion().SO3(), R)
245+
246+
nt.assert_array_almost_equal(q.SO3(), R_from_q)
247+
nt.assert_array_almost_equal(q.SO3().UnitQuaternion(), q)
248+
249+
236250
def test_shape(self):
237251
a = SO3()
238252
self.assertEqual(a._A.shape, a.shape)

0 commit comments

Comments
0 (0)
Morty Proxy This is a proxified and sanitized view of the page, visit original site.