8000 Use same tol defaul values (#107) · andybarry/spatialmath-python@a0bb12f · GitHub
[go: up one dir, main page]

Skip to content

Commit a0bb12f

Browse files
authored
Use same tol defaul values (bdaiinstitute#107)
Update the default values for tol(lerance) across the board, with the following justifications: - Using the same default value should help set user expectations, particularly when combined with updated docstrings; - If these changes break any code, it might help the user to review previous assumptions of numerical tolerances in the context of the actual use case.
1 parent 8339b8f commit a0bb12f

File tree

8 files changed

+121
-100
lines changed

8 files changed

+121
-100
lines changed

spatialmath/base/quaternions.py

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -106,13 +106,13 @@ def qnorm(q: ArrayLike4) -> float:
106106
return np.linalg.norm(q)
107107

108108

109-
def qunit(q: ArrayLike4, tol: float = 10) -> UnitQuaternionArray:
109+
def qunit(q: ArrayLike4, tol: float = 20) -> UnitQuaternionArray:
110110
"""
111111
Create a unit quaternion
112112
113113
:arg v: quaterion
114114
:type v: array_like(4)
115-
:param tol: Tolerance in multiples of eps, defaults to 10
115+
:param tol: Tolerance in multiples of eps, defaults to 20
116116
:type tol: float, optional
117117
:return: a pure quaternion
118118
:rtype: ndarray(4)
@@ -146,13 +146,13 @@ def qunit(q: ArrayLike4, tol: float = 10) -> UnitQuaternionArray:
146146
return -q
147147

148148

149-
def qisunit(q: ArrayLike4, tol: float = 100) -> bool:
149+
def qisunit(q: ArrayLike4, tol: float = 20) -> bool:
150150
"""
151151
Test if quaternion has unit length
152152
153153
:param v: quaternion
154154
:type v: array_like(4)
155-
:param tol: tolerance in units of eps, defaults to 100
155+
:param tol: tolerance in units of eps, defaults to 20
156156
:type tol: float
157157
:return: whether quaternion has unit length
158158
:rtype: bool
@@ -174,7 +174,7 @@ def qisunit(q: ArrayLike4, tol: float = 100) -> bool:
174174
def qisequal(
175175
q1: ArrayLike4,
176176
q2: ArrayLike4,
177-
tol: float = 100,
177+
tol: float = 20,
178178
unitq: Optional[bool] = False,
179179
) -> bool:
180180
...
@@ -184,13 +184,13 @@ def qisequal(
184184
def qisequal(
185185
q1: ArrayLike4,
186186
q2: ArrayLike4,
187-
tol: float = 100,
187+
tol: float = 20,
188188
unitq: Optional[bool] = True,
189189
) -> bool:
190190
...
191191

192192

193-
def qisequal(q1, q2, tol: float = 100, unitq: Optional[bool] = False):
193+
def qisequal(q1, q2, tol: float = 20, unitq: Optional[bool] = False):
194194
"""
195195
Test if quaternions are equal
196196
@@ -200,7 +200,7 @@ def qisequal(q1, q2, tol: float = 100, unitq: Optional[bool] = False):
200200
:type q2: array_like(4)
201201
:param unitq: quaternions are unit quaternions
202202
:type unitq: bool
203-
:param tol: tolerance in units of eps, defaults to 100
203+
:param tol: tolerance in units of eps, defaults to 20
204204
:type tol: float
205205
:return: whether quaternions are equal
206206
:rtype: bool
@@ -547,7 +547,7 @@ def q2r(
547547
def r2q(
548548
R: SO3Array,
549549
check: Optional[bool] = False,
550-
tol: float = 100,
550+
tol: float = 20,
551551
order: Optional[str] = "sxyz",
552552
) -> UnitQuaternionArray:
553553
"""
@@ -557,7 +557,7 @@ def r2q(
557557
:type R: ndarray(3,3)
558558
:param check: check validity of rotation matrix, default False
559559
:type check: bool
560-
:param tol: tolerance in units of eps, defaults to 100
560+
:param tol: tolerance in units of eps, defaults to 20
561561
:type tol: float
562562
:param order: the order of the returned quaternion elements. Must be 'sxyz' or
563563
'xyzs'. Defaults to 'sxyz'.
@@ -761,7 +761,11 @@ def r2q(
761761

762762

763763
def qslerp(
764-
q0: ArrayLike4, q1: ArrayLike4, s: float, shortest: Optional[bool] = False, tol: float = 10
764+
q0: ArrayLike4,
765+
q1: ArrayLike4,
766+
s: float,
767+
shortest: Optional[bool] = False,
768+
tol: float = 20,
765769
) -> UnitQuaternionArray:
766770
"""
767771
Quaternion conjugate
@@ -774,7 +778,7 @@ def qslerp(
774778
:type s: float
775779
:arg shortest: choose shortest distance [default False]
776780
:type shortest: bool
777-
:param tol: Tolerance when checking for identical quaternions, in multiples of eps, defaults to 10
781+
:param tol: Tolerance when checking for identical quaternions, in multiples of eps, defaults to 20
778782
:type tol: float, optional
779783
:return: interpolated unit-quaternion
780784
:rtype: ndarray(4)

spatialmath/base/transforms2d.py

Lines changed: 21 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -324,15 +324,15 @@ def pos2tr2(x, y=None):
324324
return T
325325

326326

327-
def ishom2(T: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(SE2):
327+
def ishom2(T: Any, check: bool = False, tol: float = 20) -> bool: # TypeGuard(SE2):
328328
"""
329329
Test if matrix belongs to SE(2)
330330
331331
:param T: SE(2) matrix to test
332332
:type T: ndarray(3,3)
333333
:param check: check validity of rotation submatrix
334334
:type check: bool
335-
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 100
335+
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
336336
:type: float
337337
:return: whether matrix is an SE(2) homogeneous transformation matrix
338338
:rtype: bool
@@ -358,19 +358,22 @@ def ishom2(T: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(
358358
return (
359359
isinstance(T, np.ndarray)
360360
and T.shape == (3, 3)
361-
and (not check or (smb.isR(T[:2, :2], tol=tol) and all(T[2, :] == np.array([0, 0, 1]))))
361+
and (
362+
not check
363+
or (smb.isR(T[:2, :2], tol=tol) and all(T[2, :] == np.array([0, 0, 1])))
364+
)
362365
)
363366

364367

365-
def isrot2(R: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(SO2):
368+
def isrot2(R: Any, check: bool = False, tol: float = 20) -> bool: # TypeGuard(SO2):
366369
"""
367370
Test if matrix belongs to SO(2)
368371
369372
:param R: SO(2) matrix to test
370373
:type R: ndarray(3,3)
371374
:param check: check validity of rotation submatrix
372375
:type check: bool
373-
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 100
376+
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
374377
:type: float
375378
:return: whether matrix is an SO(2) rotation matrix
376379
:rtype: bool
@@ -392,7 +395,11 @@ def isrot2(R: Any, check: bool = False, tol: float = 100) -> bool: # TypeGuard(
392395
393396
:seealso: isR, ishom2, isrot
394397
"""
395-
return isinstance(R, np.ndarray) and R.shape == (2, 2) and (not check or smb.isR(R, tol=tol))
398+
return (
399+
isinstance(R, np.ndarray)
400+
and R.shape == (2, 2)
401+
and (not check or smb.isR(R, tol=tol))
402+
)
396403

397404

398405
# ---------------------------------------------------------------------------------------#
@@ -438,7 +445,7 @@ def trlog2(
438445
T: SO2Array,
439446
twist: bool = False,
440447
check: bool = True,
441-
tol: float = 10,
448+
tol: float = 20,
442449
) -> so2Array:
443450
...
444451

@@ -448,7 +455,7 @@ def trlog2(
448455
T: SE2Array,
449456
twist: bool = False,
450457
check: bool = True,
451-
tol: float = 10,
458+
tol: float = 20,
452459
) -> se2Array:
453460
...
454461

@@ -458,7 +465,7 @@ def trlog2(
458465
T: SO2Array,
459466
twist: bool = True,
460467
check: bool = True,
461-
tol: float = 10,
468+
tol: float = 20,
462469
) -> float:
463470
...
464471

@@ -468,7 +475,7 @@ def trlog2(
468475
T: SE2Array,
469476
twist: bool = True,
470477
check: bool = True,
471-
tol: float = 10,
478+
tol: float = 20,
472479
) -> R3:
473480
...
474481

@@ -477,7 +484,7 @@ def trlog2(
477484
T: Union[SO2Array, SE2Array],
478485
twist: bool = False,
479486
check: bool = True,
480-
tol: float = 10,
487+
tol: float = 20,
481488
) -> Union[float, R3, so2Array, se2Array]:
482489
"""
483490
Logarithm of SO(2) or SE(2) matrix
@@ -488,7 +495,7 @@ def trlog2(
488495
:type check: bool
489496
:param twist: return a twist vector instead of matrix [default]
490497
:type twist: bool
491-
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
498+
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
492499
:type: float
493500
:return: logarithm
494501
:rtype: ndarray(3,3) or ndarray(3); or ndarray(2,2) or ndarray(1)
@@ -1016,13 +1023,13 @@ def trprint2(
10161023
return s
10171024

10181025

1019-
def _vec2s(fmt: str, v: ArrayLikePure, tol: float = 100) -> str:
1026+
def _vec2s(fmt: str, v: ArrayLikePure, tol: float = 20) -> str:
10201027
"""
10211028
Return a string representation for vector using the provided fmt.
10221029
10231030
:param fmt: format string for each value in v
10241031
:type fmt: str
1025-
:param tol: Tolerance when checking for near-zero values, in multiples of eps, defaults to 100
1032+
:param tol: Tolerance when checking for near-zero values, in multiples of eps, defaults to 20
10261033
:type tol: float, optional
10271034
:return: string representation for the vector
10281035
:rtype: str

spatialmath/base/transforms3d.py

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -349,14 +349,14 @@ def transl(x, y=None, z=None):
349349
return T
350350

351351

352-
def ishom(T: Any, check: bool = False, tol: float = 100) -> bool:
352+
def ishom(T: Any, check: bool = False, tol: float = 20) -> bool:
353353
"""
354354
Test if matrix belongs to SE(3)
355355
356356
:param T: SE(3) matrix to test
357357
:type T: numpy(4,4)
358358
:param check: check validity of rotation submatrix
359-
:param tol: Tolerance in units of eps for rotation submatrix check, defaults to 100
359+
:param tol: Tolerance in units of eps for rotation submatrix check, defaults to 20
360360
:return: whether matrix is an SE(3) homogeneous transformation matrix
361361
362362
- ``ishom(T)`` is True if the argument ``T`` is of dimension 4x4
@@ -387,14 +387,14 @@ def ishom(T: Any, check: bool = False, tol: float = 100) -> bool:
387387
)
388388

389389

390-
def isrot(R: Any, check: bool = False, tol: float = 100) -> bool:
390+
def isrot(R: Any, check: bool = False, tol: float = 20) -> bool:
391391
"""
392392
Test if matrix belongs to SO(3)
393393
394394
:param R: SO(3) matrix to test
395395
:type R: numpy(3,3)
396396
:param check: check validity of rotation submatrix
397-
:param tol: Tolerance in units of eps for rotation matrix test, defaults to 100
397+
:param tol: Tolerance in units of eps for rotation matrix test, defaults to 20
398398
:return: whether matrix is an SO(3) rotation matrix
399399
400400
- ``isrot(R)`` is True if the argument ``R`` is of dimension 3x3
@@ -713,7 +713,7 @@ def eul2tr(
713713
# ---------------------------------------------------------------------------------------#
714714

715715

716-
def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 10) -> SO3Array:
716+
def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 20) -> SO3Array:
717717
"""
718718
Create an SO(3) rotation matrix from rotation angle and axis
719719
@@ -723,7 +723,7 @@ def angvec2r(theta: float, v: ArrayLike3, unit="rad", tol: float = 10) -> SO3Arr
723723
:type unit: str
724724
:param v: 3D rotation axis
725725
:type v: array_like(3)
726-
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
726+
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
727727
:type: float
728728
:return: SO(3) rotation matrix
729729
:rtype: ndarray(3,3)
@@ -1046,7 +1046,7 @@ def tr2eul(
10461046
unit: str = "rad",
10471047
flip: bool = False,
10481048
check: bool = False,
1049-
tol: float = 10,
1049+
tol: float = 20,
10501050
) -> R3:
10511051
r"""
10521052
Convert SO(3) or SE(3) to ZYX Euler angles
@@ -1059,7 +1059,7 @@ def tr2eul(
10591059
:type flip: bool
10601060
:param check: check that rotation matrix is valid
10611061
:type check: bool
1062-
:param tol: Tolerance in units of eps for near-zero checks, defaults to 10
1062+
:param tol: Tolerance in units of eps for near-zero checks, defaults to 20
10631063
:type: float
10641064
:return: ZYZ Euler angles
10651065
:rtype: ndarray(3)
@@ -1129,7 +1129,7 @@ def tr2rpy(
11291129
unit: str = "rad",
11301130
order: str = "zyx",
11311131
check: bool = False,
1132-
tol: float = 10,
1132+
tol: float = 20,
11331133
) -> R3:
11341134
r"""
11351135
Convert SO(3) or SE(3) to roll-pitch-yaw angles
@@ -1142,7 +1142,7 @@ def tr2rpy(
11421142
:type order: str
11431143
:param check: check that rotation matrix is valid
11441144
:type check: bool
1145-
:param tol: Tolerance in units of eps, defaults to 10
1145+
:param tol: Tolerance in units of eps, defaults to 20
11461146
:type: float
11471147
:return: Roll-pitch-yaw angles
11481148
:rtype: ndarray(3)
@@ -1271,33 +1271,33 @@ def tr2rpy(
12711271
# ---------------------------------------------------------------------------------------#
12721272
@overload # pragma: no cover
12731273
def trlog(
1274-
T: SO3Array, check: bool = True, twist: bool = False, tol: float = 10
1274+
T: SO3Array, check: bool = True, twist: bool = False, tol: float = 20
12751275
) -> so3Array:
12761276
...
12771277

12781278

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

12851285

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

12901290

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

12951295

12961296
def trlog(
12971297
T: Union[SO3Array, SE3Array],
12981298
check: bool = True,
12991299
twist: bool = False,
1300-
tol: float = 10,
1300+
tol: float = 20,
13011301
) -> Union[R3, R6, so3Array, se3Array]:
13021302
"""
13031303
Logarithm of SO(3) or SE(3) matrix
@@ -1308,7 +1308,7 @@ def trlog(
13081308
:type check: bool
13091309
:param twist: return a twist vector instead of matrix [default]
13101310
:type twist: bool
1311-
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 10
1311+
:param tol: Tolerance in units of eps for zero-rotation case, defaults to 20
13121312
:type: float
13131313
:return: logarithm
13141314
:rtype: ndarray(4,4) or ndarray(3,3)

0 commit comments

Comments
 (0)
0