Skip to content

Commit 6664937

Browse files
committed
add tests
1 parent 168f4c4 commit 6664937

File tree

5 files changed

+24
-3
lines changed

5 files changed

+24
-3
lines changed

spatialmath/base/quaternions.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -549,7 +549,7 @@ def r2q(
549549
check: Optional[bool] = False,
550550
tol: float = 20,
551551
order: Optional[str] = "sxyz",
552-
shortest: bool = True,
552+
shortest: bool = False,
553553
) -> UnitQuaternionArray:
554554
"""
555555
Convert SO(3) rotation matrix to unit-quaternion
@@ -564,7 +564,7 @@ def r2q(
564564
'xyzs'. Defaults to 'sxyz'.
565565
:type order: str
566566
:param shortest: ensures the quaternion has non-negative scalar part.
567-
:type shortest: bool, default to True
567+
:type shortest: bool, default to False
568568
:return: unit-quaternion as Euler parameters
569569
:rtype: ndarray(4)
570570
:raises ValueError: for non SO(3) argument

spatialmath/base/transforms2d.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -943,6 +943,10 @@ def trinterp2(start, end, s, shortest: bool = True):
943943

944944
th0 = math.atan2(start[1, 0], start[0, 0])
945945
th1 = math.atan2(end[1, 0], end[0, 0])
946+
if shortest:
947+
delta = (th1 - th0 + math.pi) % (math.pi * 2) - math.pi
948+
delta = delta + math.pi * 2 if delta < -math.pi else delta
949+
th1 = th0 + delta
946950

947951
p0 = transl2(start)
948952
p1 = transl2(end)

spatialmath/baseposematrix.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -434,7 +434,7 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None, shorte
434434
if self.N == 2:
435435
# SO(2) or SE(2)
436436
return self.__class__(
437-
[smb.trinterp2(start=self.A, end=end, s=_s) for _s in s]
437+
[smb.trinterp2(start=self.A, end=end, s=_s, shortest=shortest) for _s in s]
438438
)
439439

440440
elif self.N == 3:

tests/base/test_quaternions.py

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -131,6 +131,13 @@ def test_rotation(self):
131131
)
132132
nt.assert_array_almost_equal(qvmul([0, 1, 0, 0], [0, 0, 1]), np.r_[0, 0, -1])
133133

134+
large_rotation = math.pi + 0.01
135+
q1 = r2q(tr.rotx(large_rotation), shortest=False)
136+
q2 = r2q(tr.rotx(large_rotation), shortest=True)
137+
self.assertLess(q1[0], 0)
138+
self.assertGreater(q2[0], 0)
139+
self.assertTrue(qisequal(q1=q1, q2=q2, unitq=True))
140+
134141
def test_slerp(self):
135142
q1 = np.r_[0, 1, 0, 0]
136143
q2 = np.r_[0, 0, 1, 0]

tests/test_pose2d.py

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -456,6 +456,16 @@ def test_interp(self):
456456
array_compare(I.interp(TT, s=1), TT)
457457
array_compare(I.interp(TT, s=0.5), SE2(1, -2, 0.3))
458458

459+
R1 = SO2(math.pi - 0.1)
460+
R2 = SO2(-math.pi + 0.2)
461+
array_compare(R1.interp(R2, s=0.5, shortest=False), SO2(0.05))
462+
array_compare(R1.interp(R2, s=0.5, shortest=True), SO2(-math.pi + 0.05))
463+
464+
T1 = SE2(0, 0, math.pi - 0.1)
465+
T2 = SE2(0, 0, -math.pi + 0.2)
466+
array_compare(T1.interp(T2, s=0.5, shortest=False), SE2(0, 0, 0.05))
467+
array_compare(T1.interp(T2, s=0.5, shortest=True), SE2(0, 0, -math.pi + 0.05))
468+
459469
def test_miscellany(self):
460470
TT = SE2(1, 2, 0.3)
461471

0 commit comments

Comments
 (0)