Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 16 additions & 12 deletions spatialmath/base/quaternions.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,13 +106,13 @@ def qnorm(q: ArrayLike4) -> float:
return np.linalg.norm(q)


def qunit(q: ArrayLike4, tol: float = 10) -> UnitQuaternionArray:
def qunit(q: ArrayLike4, tol: float = 20) -> UnitQuaternionArray:
"""
Create a unit quaternion

:arg v: quaterion
:type v: array_like(4)
:param tol: Tolerance in multiples of eps, defaults to 10
:param tol: Tolerance in multiples of eps, defaults to 20
:type tol: float, optional
:return: a pure quaternion
:rtype: ndarray(4)
Expand Down Expand Up @@ -146,13 +146,13 @@ def qunit(q: ArrayLike4, tol: float = 10) -> UnitQuaternionArray:
return -q


def qisunit(q: ArrayLike4, tol: float = 100) -> bool:
def qisunit(q: ArrayLike4, tol: float = 20) -> bool:
"""
Test if quaternion has unit length

:param v: quaternion
:type v: array_like(4)
:param tol: tolerance in units of eps, defaults to 100
:param tol: tolerance in units of eps, defaults to 20
:type tol: float
:return: whether quaternion has unit length
:rtype: bool
Expand All @@ -174,7 +174,7 @@ def qisunit(q: ArrayLike4, tol: float = 100) -> bool:
def qisequal(
q1: ArrayLike4,
q2: ArrayLike4,
tol: float = 100,
tol: float = 20,
unitq: Optional[bool] = False,
) -> bool:
...
Expand All @@ -184,13 +184,13 @@ def qisequal(
def qisequal(
q1: ArrayLike4,
q2: ArrayLike4,
tol: float = 100,
tol: float = 20,
unitq: Optional[bool] = True,
) -> bool:
...


def qisequal(q1, q2, tol: float = 100, unitq: Optional[bool] = False):
def qisequal(q1, q2, tol: float = 20, unitq: Optional[bool] = False):
"""
Test if quaternions are equal

Expand All @@ -200,7 +200,7 @@ def qisequal(q1, q2, tol: float = 100, unitq: Optional[bool] = False):
:type q2: array_like(4)
:param unitq: quaternions are unit quaternions
:type unitq: bool
:param tol: tolerance in units of eps, defaults to 100
:param tol: tolerance in units of eps, defaults to 20
:type tol: float
:return: whether quaternions are equal
:rtype: bool
Expand Down Expand Up @@ -547,7 +547,7 @@ def q2r(
def r2q(
R: SO3Array,
check: Optional[bool] = False,
tol: float = 100,
tol: float = 20,
order: Optional[str] = "sxyz",
) -> UnitQuaternionArray:
"""
Expand All @@ -557,7 +557,7 @@ def r2q(
:type R: ndarray(3,3)
:param check: check validity of rotation matrix, default False
:type check: bool
:param tol: tolerance in units of eps, defaults to 100
:param tol: tolerance in units of eps, defaults to 20
:type tol: float
:param order: the order of the returned quaternion elements. Must be 'sxyz' or
'xyzs'. Defaults to 'sxyz'.
Expand Down Expand Up @@ -761,7 +761,11 @@ def r2q(


def qslerp(
q0: ArrayLike4, q1: ArrayLike4, s: float, shortest: Optional[bool] = False, tol: float = 10
q0: ArrayLike4,
q1: ArrayLike4,
s: float,
shortest: Optional[bool] = False,
tol: float = 20,
) -> UnitQuaternionArray:
"""
Quaternion conjugate
Expand All @@ -774,7 +778,7 @@ def qslerp(
:type s: float
:arg shortest: choose shortest distance [default False]
:type shortest: bool
:param tol: Tolerance when checking for identical quaternions, in multiples of eps, defaults to 10
:param tol: Tolerance when checking for identical quaternions, in multiples of eps, defaults to 20
:type tol: float, optional
:return: interpolated unit-quaternion
:rtype: ndarray(4)
Expand Down
35 changes: 21 additions & 14 deletions spatialmath/base/transforms2d.py
Original file line number Diff line number Diff line change
Expand Up @@ -324,15 +324,15 @@ def pos2tr2(x, y=None):
return T


def ishom2(T: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(SE2):
def ishom2(T: Any, check: bool = False, tol: float = 20) -> bool: # TypeGuard(SE2):
"""
Test if matrix belongs to SE(2)

:param T: SE(2) matrix to test
:type T: ndarray(3,3)
:param check: check validity of rotation submatrix
:type check: bool
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 100
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
:type: float
:return: whether matrix is an SE(2) homogeneous transformation matrix
:rtype: bool
Expand All @@ -358,19 +358,22 @@ def ishom2(T: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(
return (
isinstance(T, np.ndarray)
and T.shape == (3, 3)
and (not check or (smb.isR(T[:2, :2], tol=tol) and all(T[2, :] == np.array([0, 0, 1]))))
and (
not check
or (smb.isR(T[:2, :2], tol=tol) and all(T[2, :] == np.array([0, 0, 1])))
)
)


def isrot2(R: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(SO2):
def isrot2(R: Any, check: bool = False, tol: float = 20) -> bool: # TypeGuard(SO2):
"""
Test if matrix belongs to SO(2)

:param R: SO(2) matrix to test
:type R: ndarray(3,3)
:param check: check validity of rotation submatrix
:type check: bool
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 100
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
:type: float
:return: whether matrix is an SO(2) rotation matrix
:rtype: bool
Expand All @@ -392,7 +395,11 @@ def isrot2(R: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(

:seealso: isR, ishom2, isrot
"""
return isinstance(R, np.ndarray) and R.shape == (2, 2) and (not check or smb.isR(R, tol=tol))
return (
isinstance(R, np.ndarray)
and R.shape == (2, 2)
and (not check or smb.isR(R, tol=tol))
)


# ---------------------------------------------------------------------------------------#
Expand Down Expand Up @@ -438,7 +445,7 @@ def trlog2(
T: SO2Array,
twist: bool = False,
check: bool = True,
tol: float = 10,
tol: float = 20,
) -> so2Array:
...

Expand All @@ -448,7 +455,7 @@ def trlog2(
T: SE2Array,
twist: bool = False,
check: bool = True,
tol: float = 10,
tol: float = 20,
) -> se2Array:
...

Expand All @@ -458,7 +465,7 @@ def trlog2(
T: SO2Array,
twist: bool = True,
check: bool = True,
tol: float = 10,
tol: float = 20,
) -> float:
...

Expand All @@ -468,7 +475,7 @@ def trlog2(
T: SE2Array,
twist: bool = True,
check: bool = True,
tol: float = 10,
tol: float = 20,
) -> R3:
...

Expand All @@ -477,7 +484,7 @@ def trlog2(
T: Union[SO2Array, SE2Array],
twist: bool = False,
check: bool = True,
tol: float = 10,
tol: float = 20,
) -> Union[float, R3, so2Array, se2Array]:
"""
Logarithm of SO(2) or SE(2) matrix
Expand All @@ -488,7 +495,7 @@ def trlog2(
:type check: bool
:param twist: return a twist vector instead of matrix [default]
:type twist: bool
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
:type: float
:return: logarithm
:rtype: ndarray(3,3) or ndarray(3); or ndarray(2,2) or ndarray(1)
Expand Down Expand Up @@ -1016,13 +1023,13 @@ def trprint2(
return s


def _vec2s(fmt: str, v: ArrayLikePure, tol: float = 100) -> str:
def _vec2s(fmt: str, v: ArrayLikePure, tol: float = 20) -> str:
"""
Return a string representation for vector using the provided fmt.

:param fmt: format string for each value in v
:type fmt: str
:param tol: Tolerance when checking for near-zero values, in multiples of eps, defaults to 100
:param tol: Tolerance when checking for near-zero values, in multiples of eps, defaults to 20
:type tol: float, optional
:return: string representation for the vector
:rtype: str
Expand Down
32 changes: 16 additions & 16 deletions spatialmath/base/transforms3d.py
Original file line number Diff line number Diff line change
Expand Up @@ -349,14 +349,14 @@ def transl(x, y=None, z=None):
return T


def ishom(T: Any, check: bool = False, tol: float = 100) -> bool:
def ishom(T: Any, check: bool = False, tol: float = 20) -> bool:
"""
Test if matrix belongs to SE(3)

:param T: SE(3) matrix to test
:type T: numpy(4,4)
:param check: check validity of rotation submatrix
:param tol: Tolerance in units of eps for rotation submatrix check, defaults to 100
:param tol: Tolerance in units of eps for rotation submatrix check, defaults to 20
:return: whether matrix is an SE(3) homogeneous transformation matrix

- ``ishom(T)`` is True if the argument ``T`` is of dimension 4x4
Expand Down Expand Up @@ -387,14 +387,14 @@ def ishom(T: Any, check: bool = False, tol: float = 100) -> bool:
)


def isrot(R: Any, check: bool = False, tol: float = 100) -> bool:
def isrot(R: Any, check: bool = False, tol: float = 20) -> bool:
"""
Test if matrix belongs to SO(3)

:param R: SO(3) matrix to test
:type R: numpy(3,3)
:param check: check validity of rotation submatrix
:param tol: Tolerance in units of eps for rotation matrix test, defaults to 100
:param tol: Tolerance in units of eps for rotation matrix test, defaults to 20
:return: whether matrix is an SO(3) rotation matrix

- ``isrot(R)`` is True if the argument ``R`` is of dimension 3x3
Expand Down Expand Up @@ -713,7 +713,7 @@ def eul2tr(
# ---------------------------------------------------------------------------------------#


def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 10) -> SO3Array:
def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 20) -> SO3Array:
"""
Create an SO(3) rotation matrix from rotation angle and axis

Expand All @@ -723,7 +723,7 @@ def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 10) -> SO3Arr
:type unit: str
:param v: 3D rotation axis
:type v: array_like(3)
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
:type: float
:return: SO(3) rotation matrix
:rtype: ndarray(3,3)
Expand Down Expand Up @@ -1046,7 +1046,7 @@ def tr2eul(
unit: str = "rad",
flip: bool = False,
check: bool = False,
tol: float = 10,
tol: float = 20,
) -> R3:
r"""
Convert SO(3) or SE(3) to ZYX Euler angles
Expand All @@ -1059,7 +1059,7 @@ def tr2eul(
:type flip: bool
:param check: check that rotation matrix is valid
:type check: bool
:param tol: Tolerance in units of eps for near-zero checks, defaults to 10
:param tol: Tolerance in units of eps for near-zero checks, defaults to 20
:type: float
:return: ZYZ Euler angles
:rtype: ndarray(3)
Expand Down Expand Up @@ -1129,7 +1129,7 @@ def tr2rpy(
unit: str = "rad",
order: str = "zyx",
check: bool = False,
tol: float = 10,
tol: float = 20,
) -> R3:
r"""
Convert SO(3) or SE(3) to roll-pitch-yaw angles
Expand All @@ -1142,7 +1142,7 @@ def tr2rpy(
:type order: str
:param check: check that rotation matrix is valid
:type check: bool
:param tol: Tolerance in units of eps, defaults to 10
:param tol: Tolerance in units of eps, defaults to 20
:type: float
:return: Roll-pitch-yaw angles
:rtype: ndarray(3)
Expand Down Expand Up @@ -1271,33 +1271,33 @@ def tr2rpy(
# ---------------------------------------------------------------------------------------#
@overload # pragma: no cover
def trlog(
T: SO3Array, check: bool = True, twist: bool = False, tol: float = 10
T: SO3Array, check: bool = True, twist: bool = False, tol: float = 20
) -> so3Array:
...


@overload # pragma: no cover
def trlog(
T: SE3Array, check: bool = True, twist: bool = False, tol: float = 10
T: SE3Array, check: bool = True, twist: bool = False, tol: float = 20
) -> se3Array:
...


@overload # pragma: no cover
def trlog(T: SO3Array, check: bool = True, twist: bool = True, tol: float = 10) -> R3:
def trlog(T: SO3Array, check: bool = True, twist: bool = True, tol: float = 20) -> R3:
...


@overload # pragma: no cover
def trlog(T: SE3Array, check: bool = True, twist: bool = True, tol: float = 10) -> R6:
def trlog(T: SE3Array, check: bool = True, twist: bool = True, tol: float = 20) -> R6:
...


def trlog(
T: Union[SO3Array, SE3Array],
check: bool = True,
twist: bool = False,
tol: float = 10,
tol: float = 20,
) -> Union[R3, R6, so3Array, se3Array]:
"""
Logarithm of SO(3) or SE(3) matrix
Expand All @@ -1308,7 +1308,7 @@ def trlog(
:type check: bool
:param twist: return a twist vector instead of matrix [default]
:type twist: bool
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
:type: float
:return: logarithm
:rtype: ndarray(4,4) or ndarray(3,3)
Expand Down
Loading