Skip to content

Commit

Permalink
add tests
Browse files Browse the repository at this point in the history
  • Loading branch information
jcao-bdai committed May 5, 2024
1 parent 168f4c4 commit 3b6e6e7
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 2 deletions.
2 changes: 1 addition & 1 deletion spatialmath/base/quaternions.py
Original file line number Diff line number Diff line change
Expand Up @@ -549,7 +549,7 @@ def r2q(
check: Optional[bool] = False,
tol: float = 20,
order: Optional[str] = "sxyz",
shortest: bool = True,
shortest: bool = False,
) -> UnitQuaternionArray:
"""
Convert SO(3) rotation matrix to unit-quaternion
Expand Down
4 changes: 4 additions & 0 deletions spatialmath/base/transforms2d.py
Original file line number Diff line number Diff line change
Expand Up @@ -943,6 +943,10 @@ def trinterp2(start, end, s, shortest: bool = True):

th0 = math.atan2(start[1, 0], start[0, 0])
th1 = math.atan2(end[1, 0], end[0, 0])
if shortest:
delta = (th1 - th0 + math.pi) % (math.pi * 2) - math.pi
delta = delta + math.pi * 2 if delta < -math.pi else delta
th1 = th0 + delta

p0 = transl2(start)
p1 = transl2(end)
Expand Down
2 changes: 1 addition & 1 deletion spatialmath/baseposematrix.py
Original file line number Diff line number Diff line change
Expand Up @@ -434,7 +434,7 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None, shorte
if self.N == 2:
# SO(2) or SE(2)
return self.__class__(
[smb.trinterp2(start=self.A, end=end, s=_s) for _s in s]
[smb.trinterp2(start=self.A, end=end, s=_s, shortest=shortest) for _s in s]
)

elif self.N == 3:
Expand Down
7 changes: 7 additions & 0 deletions tests/base/test_quaternions.py
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,13 @@ def test_rotation(self):
)
nt.assert_array_almost_equal(qvmul([0, 1, 0, 0], [0, 0, 1]), np.r_[0, 0, -1])

large_rotation = math.pi + 0.01
q1 = r2q(tr.rotx(large_rotation), shortest=False)
q2 = r2q(tr.rotx(large_rotation), shortest=True)
self.assertLess(q1[0], 0)
self.assertGreater(q2[0], 0)
self.assertTrue(qisequal(q1=q1, q2=q2, unitq=True))

def test_slerp(self):
q1 = np.r_[0, 1, 0, 0]
q2 = np.r_[0, 0, 1, 0]
Expand Down
10 changes: 10 additions & 0 deletions tests/test_pose2d.py
Original file line number Diff line number Diff line change
Expand Up @@ -456,6 +456,16 @@ def test_interp(self):
array_compare(I.interp(TT, s=1), TT)
array_compare(I.interp(TT, s=0.5), SE2(1, -2, 0.3))

R1 = SO2(math.pi - 0.1)
R2 = SO2(-math.pi + 0.2)
array_compare(R1.interp(R2, s=0.5, shortest=False), SO2(0.05))
array_compare(R1.interp(R2, s=0.5, shortest=True), SO2(-math.pi + 0.05))

T1 = SE2(0, 0, math.pi - 0.1)
T2 = SE2(0, 0, -math.pi + 0.2)
array_compare(T1.interp(T2, s=0.5, shortest=False), SE2(0, 0, 0.05))
array_compare(T1.interp(T2, s=0.5, shortest=True), SE2(0, 0, -math.pi + 0.05))

def test_miscellany(self):
TT = SE2(1, 2, 0.3)

Expand Down

0 comments on commit 3b6e6e7

Please sign in to comment.