-
Notifications
You must be signed in to change notification settings - Fork 8
Add support for the S1 (circle) manifold and its tangent space #19
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 3 commits
d7a7b3a
04e80ec
b714753
8287936
e02f79e
0a17639
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 |
---|---|---|
@@ -0,0 +1,80 @@ | ||
import dataclasses | ||
import casadi as cs | ||
|
||
from liecasadi.hints import Angle, Scalar | ||
|
||
|
||
def _wrap_to_pi(angle: Scalar) -> Scalar: | ||
"""Wrap an angle to the range [-pi, pi].""" | ||
return cs.fmod(angle + cs.pi, 2 * cs.pi) - cs.pi | ||
|
||
|
||
@dataclasses.dataclass | ||
class S1: | ||
"""Class representing the circle manifold S1.""" | ||
|
||
angle: Angle | ||
|
||
def __repr__(self) -> str: | ||
return f"S1 angle: {self.angle}" | ||
|
||
@staticmethod | ||
def Identity() -> "S1": | ||
"""Return the identity element (0 radians).""" | ||
return S1(0.0) | ||
|
||
def as_angle(self) -> Angle: | ||
"""Return the angle value.""" | ||
return self.angle | ||
|
||
def inverse(self) -> "S1": | ||
"""Return the inverse rotation.""" | ||
return S1(-self.angle) | ||
|
||
def __mul__(self, other: "S1") -> "S1": | ||
if type(self) is type(other): | ||
return S1(_wrap_to_pi(self.angle + other.angle)) | ||
raise RuntimeError("[S1: __mul__] Please multiply with an S1 object.") | ||
|
||
def __rmul__(self, other: "S1") -> "S1": | ||
return self.__mul__(other) | ||
|
||
def log(self) -> "S1Tangent": | ||
"""Return the tangent vector via the logarithm map.""" | ||
return S1Tangent(_wrap_to_pi(self.angle)) | ||
|
||
def __sub__(self, other: "S1") -> "S1Tangent": | ||
if type(self) is type(other): | ||
return S1Tangent(_wrap_to_pi(self.angle - other.angle)) | ||
raise RuntimeError("[S1: __sub__] Please subtract an S1 object.") | ||
|
||
|
||
@dataclasses.dataclass | ||
class S1Tangent: | ||
"""Tangent space element of S1.""" | ||
|
||
val: Scalar | ||
|
||
def __repr__(self) -> str: | ||
return f"S1Tangent: {self.val}" | ||
|
||
def exp(self) -> S1: | ||
"""Exponential map returning an S1 element.""" | ||
return S1(_wrap_to_pi(self.val)) | ||
|
||
def __add__(self, other: S1) -> S1: | ||
if type(other) is S1: | ||
return S1(_wrap_to_pi(other.angle + self.val)) | ||
raise RuntimeError("[S1Tangent: __add__] Please add an S1 object.") | ||
|
||
def __radd__(self, other: S1) -> S1: | ||
return self.__add__(other) | ||
|
||
def __mul__(self, scalar: float) -> "S1Tangent": | ||
edxmorgan marked this conversation as resolved.
Show resolved
Hide resolved
|
||
if isinstance(scalar, (int, float)): | ||
return S1Tangent(self.val * scalar) | ||
raise RuntimeError("[S1Tangent: __mul__] Please multiply with a scalar.") | ||
|
||
def value(self) -> Scalar: | ||
"""Return the underlying scalar value.""" | ||
return self.val |
Original file line number | Diff line number | Diff line change | ||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -2,8 +2,8 @@ | |||||||||||||||||
import numpy as np | ||||||||||||||||||
import pytest | ||||||||||||||||||
from scipy.spatial.transform import Rotation | ||||||||||||||||||
|
||||||||||||||||||
from liecasadi import SE3, SO3, SE3Tangent, SO3Tangent | ||||||||||||||||||
import casadi as cs | ||||||||||||||||||
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. With a new module, it could make sense to split the tests into multiple files. But we can do it in a different pr 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. right! Splitting the tests into separate files will make it look organized. I’ll open a PR for that. |
||||||||||||||||||
from liecasadi import SE3, SO3, S1, SE3Tangent, SO3Tangent, S1Tangent | ||||||||||||||||||
|
||||||||||||||||||
# quat generation | ||||||||||||||||||
quat = (np.random.rand(4) - 0.5) * 5 | ||||||||||||||||||
|
@@ -110,10 +110,10 @@ def test_act(): | |||||||||||||||||
mySE3_2 = SE3(pos=pos2, xyzw=quat2) | ||||||||||||||||||
|
||||||||||||||||||
|
||||||||||||||||||
# def test_inverse(): | ||||||||||||||||||
assert (mySE3.inverse().transform() - manifSE3.inverse().transform()) == pytest.approx( | ||||||||||||||||||
0.0, abs=1e-4 | ||||||||||||||||||
) | ||||||||||||||||||
def test_inverse(): | ||||||||||||||||||
assert (mySE3.inverse().transform() - manifSE3.inverse().transform()) == pytest.approx( | ||||||||||||||||||
0.0, abs=1e-4 | ||||||||||||||||||
) | ||||||||||||||||||
|
||||||||||||||||||
|
||||||||||||||||||
def test_mul(): | ||||||||||||||||||
|
@@ -148,3 +148,31 @@ def test_sub_SE3(): | |||||||||||||||||
assert (mySE3 - mySE3_2).exp().transform() - ( | ||||||||||||||||||
manifSE3 - manifSE3_2 | ||||||||||||||||||
).exp().transform() == pytest.approx(0.0, abs=1e-4) | ||||||||||||||||||
|
||||||||||||||||||
|
||||||||||||||||||
# S1 objects | ||||||||||||||||||
S1_angle = (np.random.rand() - 0.5) * 2 * np.pi | ||||||||||||||||||
myS1 = S1(S1_angle) | ||||||||||||||||||
|
||||||||||||||||||
# S1Tangent objects | ||||||||||||||||||
S1_tangent_ang = (np.random.rand() - 0.5) * 2 * np.pi | ||||||||||||||||||
myS1Tang = S1Tangent(S1_tangent_ang) | ||||||||||||||||||
|
||||||||||||||||||
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. [nitpick] Remove or utilize the unused variables
Suggested change
Copilot uses AI. Check for mistakes. Positive FeedbackNegative Feedback 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. S1_angle, myS1, S1_tangent_ang, and myS1Tang unused variables removed |
||||||||||||||||||
def test_identity(): | ||||||||||||||||||
assert S1.Identity().as_angle() == 0.0 | ||||||||||||||||||
|
||||||||||||||||||
def test_mul(): | ||||||||||||||||||
a = S1(cs.pi / 4) | ||||||||||||||||||
b = S1(cs.pi / 4) | ||||||||||||||||||
c = a * b | ||||||||||||||||||
assert float(c.as_angle()) == pytest.approx(float(cs.pi / 2)) | ||||||||||||||||||
|
||||||||||||||||||
def test_sub_and_log_exp(): | ||||||||||||||||||
a = S1(cs.pi / 3) | ||||||||||||||||||
b = S1(cs.pi / 6) | ||||||||||||||||||
diff = a - b | ||||||||||||||||||
rebuilt = diff.exp() * b | ||||||||||||||||||
assert float(rebuilt.as_angle()) == pytest.approx(float(cs.pi / 3)) | ||||||||||||||||||
|
||||||||||||||||||
tangent = a.log() | ||||||||||||||||||
assert float(tangent.exp().as_angle()) == pytest.approx(float(cs.pi / 3)) | ||||||||||||||||||
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. End of line missing! |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm not sure this function is continuous and differentiable :/
A possible solution could be to use something like
which should be continuous.
The issue is when
angle == 0.0
, but maybe adding a small tolerancenp.finfo().eps
could solve this.@edxmorgan what do you think?
cc @edxmorgan