From ad98b0ee011eb33249e92df69b74f14ce2eab509 Mon Sep 17 00:00:00 2001 From: Brian Okorn Date: Wed, 10 Jan 2024 13:33:13 -0500 Subject: [PATCH 1/7] Fixed fall through error in binary operation (#117) Fixes https://github.com/bdaiinstitute/spatialmath-python/issues/116 and adds more test coverage. --- spatialmath/baseposematrix.py | 6 +++++- tests/test_pose3d.py | 39 +++++++++++++++++++++++++++++++++++ 2 files changed, 44 insertions(+), 1 deletion(-) diff --git a/spatialmath/baseposematrix.py b/spatialmath/baseposematrix.py index da1421e9..379a5439 100644 --- a/spatialmath/baseposematrix.py +++ b/spatialmath/baseposematrix.py @@ -1657,7 +1657,7 @@ def _op2(left, right: Self, op: Callable): # pylint: disable=no-self-argument ========= ========== ==== ================================ """ - if isinstance(right, left.__class__): + if isinstance(right, left.__class__) or isinstance(left, right.__class__): # class by class if len(left) == 1: if len(right) == 1: @@ -1683,6 +1683,10 @@ def _op2(left, right: Self, op: Callable): # pylint: disable=no-self-argument return op(left.A, right) else: return [op(x, right) for x in left.A] + else: + raise TypeError( + f"Invalid type ({right.__class__}) for binary operation with {left.__class__}" + ) if __name__ == "__main__": diff --git a/tests/test_pose3d.py b/tests/test_pose3d.py index 04ed1e12..7132bddc 100755 --- a/tests/test_pose3d.py +++ b/tests/test_pose3d.py @@ -1260,6 +1260,45 @@ def test_arith_vect(self): array_compare(a[1], ry - 1) array_compare(a[2], rz - 1) + def test_angle(self): + # angle between SO3's + r1 = SO3.Rx(0.1) + r2 = SO3.Rx(0.2) + for metric in range(6): + self.assertAlmostEqual(r1.angdist(other=r1, metric=metric), 0.0) + self.assertGreater(r1.angdist(other=r2, metric=metric), 0.0) + self.assertAlmostEqual( + r1.angdist(other=r2, metric=metric), r2.angdist(other=r1, metric=metric) + ) + # angle between SE3's + p1a, p1b = SE3.Rx(0.1), SE3.Rx(0.1, t=(1, 2, 3)) + p2a, p2b = SE3.Rx(0.2), SE3.Rx(0.2, t=(3, 2, 1)) + for metric in range(6): + self.assertAlmostEqual(p1a.angdist(other=p1a, metric=metric), 0.0) + self.assertGreater(p1a.angdist(other=p2a, metric=metric), 0.0) + self.assertAlmostEqual(p1a.angdist(other=p1b, metric=metric), 0.0) + self.assertAlmostEqual( + p1a.angdist(other=p2a, metric=metric), + p2a.angdist(other=p1a, metric=metric), + ) + self.assertAlmostEqual( + p1a.angdist(other=p2a, metric=metric), + p1a.angdist(other=p2b, metric=metric), + ) + # angdist is not implemented for mismatched types + with self.assertRaises(ValueError): + _ = r1.angdist(p1a) + + with self.assertRaises(ValueError): + _ = r1._op2(right=p1a, op=r1.angdist) + + with self.assertRaises(ValueError): + _ = p1a._op2(right=r1, op=p1a.angdist) + + # in general, the _op2 interface enforces an isinstance check. + with self.assertRaises(TypeError): + _ = r1._op2(right=(1, 0, 0), op=r1.angdist) + def test_functions(self): # inv # .T From 470962c3a77fda1bfd0022fea92a9b4474b1de97 Mon Sep 17 00:00:00 2001 From: Mark Yeatman <129521731+myeatman-bdai@users.noreply.github.com> Date: Fri, 23 Feb 2024 15:08:50 -0500 Subject: [PATCH 2/7] Fix UnitQuaternion constructor with v keyword. (#118) --- spatialmath/quaternion.py | 8 ++++++++ tests/test_quaternion.py | 6 ++++++ 2 files changed, 14 insertions(+) diff --git a/spatialmath/quaternion.py b/spatialmath/quaternion.py index be0ea2f0..26d8093a 100644 --- a/spatialmath/quaternion.py +++ b/spatialmath/quaternion.py @@ -77,6 +77,9 @@ def __init__(self, s: Any = None, v=None, check: Optional[bool] = True): """ super().__init__() + if s is None and smb.isvector(v, 4): + v,s = (s,v) + if v is None: # single argument if super().arghandler(s, check=False): @@ -979,6 +982,11 @@ def __init__( """ super().__init__() + # handle: UnitQuaternion(v)`` constructs a unit quaternion with specified elements + # from ``v`` which is a 4-vector given as a list, tuple, or ndarray(4) + if s is None and smb.isvector(v, 4): + v,s = (s,v) + if v is None: # single argument if super().arghandler(s, check=check): diff --git a/tests/test_quaternion.py b/tests/test_quaternion.py index 0f2ac871..791e27bf 100644 --- a/tests/test_quaternion.py +++ b/tests/test_quaternion.py @@ -70,6 +70,9 @@ def test_constructor(self): qcompare(UnitQuaternion(2, [0, 0, 0]), np.r_[1, 0, 0, 0]) qcompare(UnitQuaternion(-2, [0, 0, 0]), np.r_[1, 0, 0, 0]) + qcompare(UnitQuaternion([1, 2, 3, 4]), UnitQuaternion(v = [1, 2, 3, 4])) + qcompare(UnitQuaternion(s = 1, v = [2, 3, 4]), UnitQuaternion(v = [1, 2, 3, 4])) + # from R qcompare(UnitQuaternion(np.eye(3)), [1, 0, 0, 0]) @@ -753,6 +756,9 @@ def test_constructor(self): nt.assert_array_almost_equal(Quaternion(2, [0, 0, 0]).vec, [2, 0, 0, 0]) nt.assert_array_almost_equal(Quaternion(-2, [0, 0, 0]).vec, [-2, 0, 0, 0]) + qcompare(Quaternion([1, 2, 3, 4]), Quaternion(v = [1, 2, 3, 4])) + qcompare(Quaternion(s = 1, v = [2, 3, 4]), Quaternion(v = [1, 2, 3, 4])) + # pure v = [5, 6, 7] nt.assert_array_almost_equal( From b16b34f1725980c8924b8a49e5f5fe0671c6a486 Mon Sep 17 00:00:00 2001 From: tjdwill Date: Wed, 17 Apr 2024 20:48:02 -0500 Subject: [PATCH 3/7] Fixed code block bugs and clarified a sentence in intro.rst (#120) --- docs/source/intro.rst | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/docs/source/intro.rst b/docs/source/intro.rst index 6e778a90..8f3d1297 100644 --- a/docs/source/intro.rst +++ b/docs/source/intro.rst @@ -153,8 +153,8 @@ The implementation of composition depends on the class: * for unit-quaternions composition is the Hamilton product of the underlying vector value, * for twists it is the logarithm of the product of exponentiating the two twists -The ``**`` operator denotes repeated composition, so the exponent must be an integer. If the negative exponent the repeated multiplication -is performed then the inverse is taken. +The ``**`` operator denotes repeated composition, so the exponent must be an integer. If the exponent is negative, repeated multiplication +is performed and then the inverse is taken. The group inverse is given by the ``inv()`` method: @@ -214,6 +214,8 @@ or, in the case of a scalar, broadcast to each element: .. runblock:: pycon >>> from spatialmath import * + >>> T = SE3() + >>> T >>> T - 1 >>> 2 * T @@ -609,7 +611,7 @@ column vectors. .. runblock:: pycon >>> from spatialmath.base import * - >>> q = quat.qqmul([1,2,3,4], [5,6,7,8]) + >>> q = qqmul([1,2,3,4], [5,6,7,8]) >>> q >>> qprint(q) >>> qnorm(q) From 3a8cb036b547ccee9c00fa53fd60d238e3484379 Mon Sep 17 00:00:00 2001 From: Brian Okorn Date: Mon, 13 May 2024 08:53:23 -0400 Subject: [PATCH 4/7] Created internal quaternion conversion function for SO3 (#119) --- spatialmath/pose3d.py | 26 ++++++++++++++++++++++++++ tests/test_pose3d.py | 16 +++++++++++++++- 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/spatialmath/pose3d.py b/spatialmath/pose3d.py index 83d179ac..4c2dae06 100644 --- a/spatialmath/pose3d.py +++ b/spatialmath/pose3d.py @@ -34,6 +34,9 @@ from spatialmath.twist import Twist3 +from typing import TYPE_CHECKING +if TYPE_CHECKING: + from spatialmath.quaternion import UnitQuaternion # ============================== SO3 =====================================# @@ -834,6 +837,29 @@ def Exp( else: return cls(smb.trexp(cast(R3, S), check=check), check=False) + def UnitQuaternion(self) -> UnitQuaternion: + """ + SO3 as a unit quaternion instance + + :return: a unit quaternion representation + :rtype: UnitQuaternion instance + + ``R.UnitQuaternion()`` is an ``UnitQuaternion`` instance representing the same rotation + as the SO3 rotation ``R``. + + Example: + + .. runblock:: pycon + + >>> from spatialmath import SO3 + >>> SO3.Rz(0.3).UnitQuaternion() + + """ + # Function level import to avoid circular dependencies + from spatialmath import UnitQuaternion + + return UnitQuaternion(smb.r2q(self.R), check=False) + def angdist(self, other: SO3, metric: int = 6) -> Union[float, ndarray]: r""" Angular distance metric between rotations diff --git a/tests/test_pose3d.py b/tests/test_pose3d.py index 7132bddc..58c60586 100755 --- a/tests/test_pose3d.py +++ b/tests/test_pose3d.py @@ -8,7 +8,7 @@ we will assume that the primitives rotx,trotx, etc. all work """ from math import pi -from spatialmath import SE3, SO3, SE2 +from spatialmath import SE3, SO3, SE2, UnitQuaternion import numpy as np from spatialmath.base import * from spatialmath.baseposematrix import BasePoseMatrix @@ -233,6 +233,20 @@ def test_constructor_TwoVec(self): # x axis should equal normalized x vector nt.assert_almost_equal(R.R[:, 0], v3 / np.linalg.norm(v3), 5) + def test_conversion(self): + R = SO3.AngleAxis(0.7, [1,2,3]) + q = UnitQuaternion([11,7,3,-6]) + + R_from_q = SO3(q.R) + q_from_R = UnitQuaternion(R) + + nt.assert_array_almost_equal(R.UnitQuaternion(), q_from_R) + nt.assert_array_almost_equal(R.UnitQuaternion().SO3(), R) + + nt.assert_array_almost_equal(q.SO3(), R_from_q) + nt.assert_array_almost_equal(q.SO3().UnitQuaternion(), q) + + def test_shape(self): a = SO3() self.assertEqual(a._A.shape, a.shape) From bc6103aa4c75871d2109f7b89a96237280f959d4 Mon Sep 17 00:00:00 2001 From: Jien Cao <135634522+jcao-bdai@users.noreply.github.com> Date: Mon, 13 May 2024 14:54:44 +0200 Subject: [PATCH 5/7] Bump up setup-python action version; exclude macos-latest+python3.7 (#124) --- .github/workflows/master.yml | 9 ++++++--- pyproject.toml | 1 + 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/.github/workflows/master.yml b/.github/workflows/master.yml index 58470d8a..f45b9eea 100644 --- a/.github/workflows/master.yml +++ b/.github/workflows/master.yml @@ -17,12 +17,15 @@ jobs: strategy: matrix: os: [windows-latest, ubuntu-latest, macos-latest] - python-version: ["3.7", "3.8", "3.9", "3.10", "3.11"] + python-version: ["3.7", "3.8", "3.9", "3.10", "3.11", "3.12"] + exclude: + - os: macos-latest + python-version: "3.7" steps: - uses: actions/checkout@v2 - name: Set up Python ${{ matrix.python-version }} - uses: actions/setup-python@v1 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} - name: Install dependencies @@ -43,7 +46,7 @@ jobs: steps: - uses: actions/checkout@v2 - name: Set up Python 3.7 - uses: actions/setup-python@v1 + uses: actions/setup-python@v5 with: python-version: 3.7 - name: Install dependencies diff --git a/pyproject.toml b/pyproject.toml index 50692ee4..802ac89c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -17,6 +17,7 @@ classifiers = [ "Programming Language :: Python :: 3.9", "Programming Language :: Python :: 3.10", "Programming Language :: Python :: 3.11", + "Programming Language :: Python :: 3.12", "License :: OSI Approved :: MIT License", "Operating System :: OS Independent", From 1cf7d92e2c07debf664c9b33cf15037c4acdf93b Mon Sep 17 00:00:00 2001 From: Jien Cao <135634522+jcao-bdai@users.noreply.github.com> Date: Mon, 13 May 2024 16:27:43 +0200 Subject: [PATCH 6/7] =?UTF-8?q?[Issue-122]=20Pass=20shortest=20arg=20for?= =?UTF-8?q?=20interp;=20optionally=20enforce=20non-negative=20scalar=20?= =?UTF-8?q?=E2=80=A6=20(#123)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- spatialmath/base/quaternions.py | 6 ++++++ spatialmath/base/transforms2d.py | 12 +++++++++--- spatialmath/base/transforms3d.py | 16 +++++++++------- spatialmath/baseposematrix.py | 8 +++++--- tests/base/test_quaternions.py | 7 +++++++ tests/test_pose2d.py | 10 ++++++++++ 6 files changed, 46 insertions(+), 13 deletions(-) diff --git a/spatialmath/base/quaternions.py b/spatialmath/base/quaternions.py index 77efe640..0adf77ca 100755 --- a/spatialmath/base/quaternions.py +++ b/spatialmath/base/quaternions.py @@ -549,6 +549,7 @@ def r2q( check: Optional[bool] = False, tol: float = 20, order: Optional[str] = "sxyz", + shortest: bool = False, ) -> UnitQuaternionArray: """ Convert SO(3) rotation matrix to unit-quaternion @@ -562,6 +563,8 @@ def r2q( :param order: the order of the returned quaternion elements. Must be 'sxyz' or 'xyzs'. Defaults to 'sxyz'. :type order: str + :param shortest: ensures the quaternion has non-negative scalar part. + :type shortest: bool, default to False :return: unit-quaternion as Euler parameters :rtype: ndarray(4) :raises ValueError: for non SO(3) argument @@ -633,6 +636,9 @@ def r2q( e[1] = math.copysign(e[1], R[0, 2] + R[2, 0]) e[2] = math.copysign(e[2], R[2, 1] + R[1, 2]) + if shortest and e[0] < 0: + e = -e + if order == "sxyz": return e elif order == "xyzs": diff --git a/spatialmath/base/transforms2d.py b/spatialmath/base/transforms2d.py index 669c8fdd..c64ed036 100644 --- a/spatialmath/base/transforms2d.py +++ b/spatialmath/base/transforms2d.py @@ -853,16 +853,16 @@ def tr2jac2(T: SE2Array) -> R3x3: @overload -def trinterp2(start: Optional[SO2Array], end: SO2Array, s: float) -> SO2Array: +def trinterp2(start: Optional[SO2Array], end: SO2Array, s: float, shortest: bool = True) -> SO2Array: ... @overload -def trinterp2(start: Optional[SE2Array], end: SE2Array, s: float) -> SE2Array: +def trinterp2(start: Optional[SE2Array], end: SE2Array, s: float, shortest: bool = True) -> SE2Array: ... -def trinterp2(start, end, s): +def trinterp2(start, end, s, shortest: bool = True): """ Interpolate SE(2) or SO(2) matrices @@ -872,6 +872,8 @@ def trinterp2(start, end, s): :type end: ndarray(3,3) or ndarray(2,2) :param s: interpolation coefficient, range 0 to 1 :type s: float + :param shortest: take the shortest path along the great circle for the rotation + :type shortest: bool, default to True :return: interpolated SE(2) or SO(2) matrix value :rtype: ndarray(3,3) or ndarray(2,2) :raises ValueError: bad arguments @@ -917,6 +919,8 @@ def trinterp2(start, end, s): th0 = math.atan2(start[1, 0], start[0, 0]) th1 = math.atan2(end[1, 0], end[0, 0]) + if shortest: + th1 = th0 + smb.wrap_mpi_pi(th1 - th0) th = th0 * (1 - s) + s * th1 @@ -937,6 +941,8 @@ def trinterp2(start, end, s): th0 = math.atan2(start[1, 0], start[0, 0]) th1 = math.atan2(end[1, 0], end[0, 0]) + if shortest: + th1 = th0 + smb.wrap_mpi_pi(th1 - th0) p0 = transl2(start) p1 = transl2(end) diff --git a/spatialmath/base/transforms3d.py b/spatialmath/base/transforms3d.py index 376af9ff..ceff8732 100644 --- a/spatialmath/base/transforms3d.py +++ b/spatialmath/base/transforms3d.py @@ -1605,16 +1605,16 @@ def trnorm(T: SE3Array) -> SE3Array: @overload -def trinterp(start: Optional[SO3Array], end: SO3Array, s: float) -> SO3Array: +def trinterp(start: Optional[SO3Array], end: SO3Array, s: float, shortest: bool = True) -> SO3Array: ... @overload -def trinterp(start: Optional[SE3Array], end: SE3Array, s: float) -> SE3Array: +def trinterp(start: Optional[SE3Array], end: SE3Array, s: float, shortest: bool = True) -> SE3Array: ... -def trinterp(start, end, s): +def trinterp(start, end, s, shortest=True): """ Interpolate SE(3) matrices @@ -1624,6 +1624,8 @@ def trinterp(start, end, s): :type end: ndarray(4,4) or ndarray(3,3) :param s: interpolation coefficient, range 0 to 1 :type s: float + :param shortest: take the shortest path along the great circle for the rotation + :type shortest: bool, default to True :return: interpolated SE(3) or SO(3) matrix value :rtype: ndarray(4,4) or ndarray(3,3) :raises ValueError: bad arguments @@ -1663,12 +1665,12 @@ def trinterp(start, end, s): if start is None: # TRINTERP(T, s) q0 = r2q(end) - qr = qslerp(qeye(), q0, s) + qr = qslerp(qeye(), q0, s, shortest=shortest) else: # TRINTERP(T0, T1, s) q0 = r2q(start) q1 = r2q(end) - qr = qslerp(q0, q1, s) + qr = qslerp(q0, q1, s, shortest=shortest) return q2r(qr) @@ -1679,7 +1681,7 @@ def trinterp(start, end, s): q0 = r2q(t2r(end)) p0 = transl(end) - qr = qslerp(qeye(), q0, s) + qr = qslerp(qeye(), q0, s, shortest=shortest) pr = s * p0 else: # TRINTERP(T0, T1, s) @@ -1689,7 +1691,7 @@ def trinterp(start, end, s): p0 = transl(start) p1 = transl(end) - qr = qslerp(q0, q1, s) + qr = qslerp(q0, q1, s, shortest=shortest) pr = p0 * (1 - s) + s * p1 return rt2tr(q2r(qr), pr) diff --git a/spatialmath/baseposematrix.py b/spatialmath/baseposematrix.py index 379a5439..1a850600 100644 --- a/spatialmath/baseposematrix.py +++ b/spatialmath/baseposematrix.py @@ -377,7 +377,7 @@ def log(self, twist: Optional[bool] = False) -> Union[NDArray, List[NDArray]]: else: return log - def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Self: + def interp(self, end: Optional[bool] = None, s: Union[int, float] = None, shortest: bool = True) -> Self: """ Interpolate between poses (superclass method) @@ -385,6 +385,8 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel :type end: same as ``self`` :param s: interpolation coefficient, range 0 to 1, or number of steps :type s: array_like or int + :param shortest: take the shortest path along the great circle for the rotation + :type shortest: bool, default to True :return: interpolated pose :rtype: same as ``self`` @@ -432,13 +434,13 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel 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: # SO(3) or SE(3) return self.__class__( - [smb.trinterp(start=self.A, end=end, s=_s) for _s in s] + [smb.trinterp(start=self.A, end=end, s=_s, shortest=shortest) for _s in s] ) def interp1(self, s: float = None) -> Self: diff --git a/tests/base/test_quaternions.py b/tests/base/test_quaternions.py index 54977c20..c512c6d2 100644 --- a/tests/base/test_quaternions.py +++ b/tests/base/test_quaternions.py @@ -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] diff --git a/tests/test_pose2d.py b/tests/test_pose2d.py index e45cc919..d6d96813 100755 --- a/tests/test_pose2d.py +++ b/tests/test_pose2d.py @@ -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) From 43d9a95eb50b708a226f27b357c7c1baed3442ce Mon Sep 17 00:00:00 2001 From: Jien Cao <135634522+jcao-bdai@users.noreply.github.com> Date: Mon, 13 May 2024 16:47:33 +0200 Subject: [PATCH 7/7] prepare release minor updates (#125) --- .github/workflows/publish.yml | 2 +- .github/workflows/sphinx.yml | 2 +- pyproject.toml | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/publish.yml b/.github/workflows/publish.yml index c2cc6854..fc49c0ed 100644 --- a/.github/workflows/publish.yml +++ b/.github/workflows/publish.yml @@ -21,7 +21,7 @@ jobs: steps: - uses: actions/checkout@v2 - name: Set up Python - uses: actions/setup-python@v2 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} - name: Install dependencies diff --git a/.github/workflows/sphinx.yml b/.github/workflows/sphinx.yml index 127b0576..7ce7d443 100644 --- a/.github/workflows/sphinx.yml +++ b/.github/workflows/sphinx.yml @@ -10,7 +10,7 @@ jobs: steps: - uses: actions/checkout@v2 - name: Set up Python 3.7 - uses: actions/setup-python@v1 + uses: actions/setup-python@v5 with: python-version: 3.7 - name: Install dependencies diff --git a/pyproject.toml b/pyproject.toml index 802ac89c..9e309b81 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [project] name = "spatialmath-python" -version = "1.1.9" +version = "1.1.10" authors = [ { name="Peter Corke", email="rvc@petercorke.com" }, ]