-
Notifications
You must be signed in to change notification settings - Fork 94
compute mean of a set of rotations #160
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 11 commits
b63567d
75e6e87
4de94b0
fba2742
629bb05
be59431
4752a59
80e0928
e00aa2d
c071234
b6c6557
7c1c1f6
05f5655
ee54d5d
d8249b8
04cbe7f
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -843,22 +843,22 @@ def Exp( | |
|
||
def UnitQuaternion(self) -> UnitQuaternion: | ||
""" | ||
SO3 as a unit quaternion instance | ||
SO3 as a unit quaternion instance | ||
|
||
:return: a unit quaternion representation | ||
:rtype: UnitQuaternion instance | ||
:return: a unit quaternion representation | ||
:rtype: UnitQuaternion instance | ||
|
||
``R.UnitQuaternion()`` is an ``UnitQuaternion`` instance representing the same rotation | ||
as the SO3 rotation ``R``. | ||
``R.UnitQuaternion()`` is an ``UnitQuaternion`` instance representing the same rotation | ||
as the SO3 rotation ``R``. | ||
|
||
Example: | ||
Example: | ||
|
||
.. runblock:: pycon | ||
.. runblock:: pycon | ||
|
||
>>> from spatialmath import SO3 | ||
>>> SO3.Rz(0.3).UnitQuaternion() | ||
>>> from spatialmath import SO3 | ||
>>> SO3.Rz(0.3).UnitQuaternion() | ||
|
||
""" | ||
""" | ||
# Function level import to avoid circular dependencies | ||
from spatialmath import UnitQuaternion | ||
|
||
|
@@ -931,6 +931,29 @@ def angdist(self, other: SO3, metric: int = 6) -> Union[float, ndarray]: | |
else: | ||
return ad | ||
|
||
def mean(self, tol: float = 20) -> SO3: | ||
"""Mean of a set of rotations | ||
|
||
:param tol: iteration tolerance in units of eps, defaults to 20 | ||
:type tol: float, optional | ||
:return: the mean rotation | ||
:rtype: :class:`SO3` instance. | ||
|
||
Computes the Karcher mean of the set of rotations within the SO(3) instance. | ||
|
||
:references: | ||
- `**Hartley, Trumpf** - "Rotation Averaging" - IJCV 2011 <https://users.cecs.anu.edu.au/~hartley/Papers/PDF/Hartley-Trumpf:Rotation-averaging:IJCV.pdf>`_ | ||
- `Karcher mean <https://en.wikipedia.org/wiki/Karcher_mean`_ | ||
""" | ||
|
||
eta = tol * np.finfo(float).eps | ||
R_mean = self[0] # initial guess | ||
while True: | ||
r = np.dstack((self.inv() * self).log()).mean(axis=2) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It's unclear to me what section of the reference paper outlines this algorithm (admittedly, I did not thoroughly read it) . Would you mind pointing it out to me? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I've clarified that. |
||
if np.linalg.norm(r) < eta: | ||
return R_mean | ||
R_mean = R_mean @ self.Exp(r) # update estimate and normalize | ||
|
||
|
||
# ============================== SE3 =====================================# | ||
|
||
|
Uh oh!
There was an error while loading. Please reload this page.