Skip to content

Commit 550d6fb

Browse files
#165 use qunit in trinterp (#166)
Co-authored-by: Mark Yeatman <[email protected]>
1 parent 4c68fa9 commit 550d6fb

File tree

2 files changed

+43
-3
lines changed

2 files changed

+43
-3
lines changed

spatialmath/base/transforms3d.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
tr2rt,
4444
Ab2M,
4545
)
46-
from spatialmath.base.quaternions import r2q, q2r, qeye, qslerp
46+
from spatialmath.base.quaternions import r2q, q2r, qeye, qslerp, qunit
4747
from spatialmath.base.graphics import plotvol3, axes_logic
4848
from spatialmath.base.animate import Animate
4949
import spatialmath.base.symbolic as sym
@@ -1675,7 +1675,7 @@ def trinterp(start, end, s, shortest=True):
16751675
q1 = r2q(end)
16761676
qr = qslerp(q0, q1, s, shortest=shortest)
16771677

1678-
return q2r(qr)
1678+
return q2r(qunit(qr))
16791679

16801680
elif ismatrix(end, (4, 4)):
16811681
# SE(3) case
@@ -1697,7 +1697,7 @@ def trinterp(start, end, s, shortest=True):
16971697
qr = qslerp(q0, q1, s, shortest=shortest)
16981698
pr = p0 * (1 - s) + s * p1
16991699

1700-
return rt2tr(q2r(qr), pr)
1700+
return rt2tr(q2r(qunit(qr)), pr)
17011701
else:
17021702
return ValueError("Argument must be SO(3) or SE(3)")
17031703

tests/test_pose3d.py

+40
Original file line numberDiff line numberDiff line change
@@ -1389,6 +1389,46 @@ def test_rtvec(self):
13891389
nt.assert_equal(rvec, [0, 1, 0])
13901390
nt.assert_equal(tvec, [2, 3, 4])
13911391

1392+
def test_interp(self):
1393+
# This data is taken from https://github.com/bdaiinstitute/spatialmath-python/issues/165
1394+
se3_1 = SE3()
1395+
se3_1.t = np.array(
1396+
[0.5705748101710814, 0.29623210833184527, 0.10764106509086407]
1397+
)
1398+
se3_1.R = np.array(
1399+
[
1400+
[0.2852875203191073, 0.9581330588259315, -0.024332536551692617],
1401+
[0.9582072394229962, -0.28568756930438033, -0.014882844564011068],
1402+
[-0.021211248608609852, -0.019069722856395098, -0.9995931315303468],
1403+
]
1404+
)
1405+
assert SE3.isvalid(se3_1.A)
1406+
1407+
se3_2 = SE3()
1408+
se3_2.t = np.array(
1409+
[0.5150284150005691, 0.25796537207802533, 0.1558725490743694]
1410+
)
1411+
se3_2.R = np.array(
1412+
[
1413+
[0.42058255728234184, 0.9064420651629983, -0.038380919906699236],
1414+
[0.9070822373513454, -0.4209501599465646, -0.0016665901233428627],
1415+
[-0.01766712176680449, -0.0341137119645545, -0.9992617912561634],
1416+
]
1417+
)
1418+
assert SE3.isvalid(se3_2.A)
1419+
1420+
path_se3 = se3_1.interp(end=se3_2, s=15, shortest=False)
1421+
1422+
angle = None
1423+
for i in range(len(path_se3) - 1):
1424+
assert SE3.isvalid(path_se3[i].A)
1425+
1426+
if angle is None:
1427+
angle = path_se3[i].angdist(path_se3[i + 1])
1428+
else:
1429+
test_angle = path_se3[i].angdist(path_se3[i + 1])
1430+
assert abs(test_angle - angle) < 1e-6
1431+
13921432

13931433
# ---------------------------------------------------------------------------------------#
13941434
if __name__ == "__main__":

0 commit comments

Comments
 (0)