8000 exceptions · StephLin/spatialmath-python@14141cb · GitHub
[go: up one dir, main page]

Skip to content

Commit 14141cb

Browse files
committed
exceptions
add doco about exceptions raised expunge all instances of assert, raise exception instead
1 parent b7fa021 commit 14141cb

File tree

5 files changed

+88
-52
lines changed

5 files changed

+88
-52
lines changed

spatialmath/base/argcheck.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ def assertmatrix(m, shape=None):
4747
:param shape: required shape
4848
:type shape: 2-tuple
4949
:raises TypeError: if value is not a real Numpy array
50-
:raise ValueError: if value is not of the specified shape
50+
:raises ValueError: if value is not of the specified shape
5151
5252
Tests if the argument is a real 2D matrix with a specified shape ``shape``
5353
but the value ``None`` indicate an unspecified (wildcard, don't care)
@@ -124,6 +124,8 @@ def getmatrix(m, shape):
124124
:raises TypeError: if ``m`` is not required type
125125
:return: a 2D array
126126
:rtype: NumPy ndarray
127+
:raises TypeError: if value is not a scalar or Numpy array
128+
:raises ValueError: if value is not of the specified shape
127129
128130
``getmatrix(m, shape)`` is a 2D matrix with shape ``shape`` formed from
129131
``m`` which can be a 2D array, 1D array-like or a scalar.
@@ -220,8 +222,8 @@ def getvector(v, dim=None, out='array', dtype=np.float64):
220222
:param dtype: datatype for numPy array return (default np.float64)
221223
:type dtype: numPy type
222224
:return: vector value in specified format
223-
:raise TypeError: value is not a list or NumPy array
224-
:raise ValueError: incorrect number of elements
225+
:raises TypeError: value is not a list or NumPy array
226+
:raises ValueError: incorrect number of elements
225227
226228
- ``getvector(vec)`` is ``vec`` converted to the output format ``out``
227229
where ``vec`` is any of:
@@ -405,6 +407,7 @@ def getunit(v, unit):
405407
:type unit: str
406408
:return: the converted value in radians
407409
:rtype: array_like
410+
:raises ValueError: argument is not a valid angular unit
408411
409412
.. runblock:: pycon
410413

spatialmath/base/quaternions.py

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ def unit(q, tol=10):
8787
:type v: array_like
8888
:return: a pure quaternion
8989
:rtype: numpy.ndarray, shape=(4,)
90-
:raises ValueError: if the quaternion has zero norm
90+
:raises ValueError: quaternion has (near) zero norm
9191
9292
Creates a unit quaternion, with unit norm, by scaling the input quaternion.
9393
@@ -104,7 +104,8 @@ def unit(q, tol=10):
104104
"""
105105
q = base.getvector(q, 4)
106106
nm = np.linalg.norm(q)
107-
assert abs(nm) > tol * _eps, 'cannot normalize (near) zero length quaternion'
107+
if abs(nm) < tol * _eps:
108+
raise ValueError("cannot normalize (near) zero length quaternion")
108109
return q / nm
109110

110111

@@ -212,7 +213,6 @@ def v2q(v):
212213
:type v: array_like
213214
:return: a unit quaternion
214215
:rtype: numpy.ndarray, shape=(4,)
215-
:raises ValueError:
216216
217217
Returns a unit-quaternion reconsituted from just its vector part. Assumes
218218
that the scalar part was positive, so :math:`s = \sqrt{1-||v||}`.
@@ -343,6 +343,7 @@ def qpow(q, power):
343343
:type power: int
344344
:return: input quaternion raised to the specified power
345345
:rtype: numpy.ndarray, shape=(4,)
346+
:raises ValueError: if exponent is non integer
346347
347348
Raises a quaternion to the specified power using repeated multiplication.
348349
@@ -363,7 +364,8 @@ def qpow(q, power):
363364
:SymPy: supported for ``q`` but not ``power``.
364365
"""
365366
q = base.getvector(q, 4)
366-
assert isinstance(power, int), "Power must be an integer"
367+
if not isinstance(power, int):
368+
raise ValueError("Power must be an integer")
367369
qr = eye()
368370
for _ in range(0, abs(power)):
369371
qr = qqmul(qr, q)
@@ -456,9 +458,8 @@ def r2q(R, check=False, tol=100):
456458
457459
:seealso: :func:`q2r`
458460
"""
459-
assert R.shape == (3, 3) and base.isR(R), "Argument must be 3x3 rotation matrix"
460-
if check:
461-
assert base.isR(R, tol=tol), "Argument must be a valid SO(3) matrix"
461+
if not base.isrot(R, check=check, tol=tol):
462+
raise ValueError("Argument must be a valid SO(3) matrix")
462463

463464
qs = math.sqrt(max(0, np.trace(R) + 1)) / 2.0
464465
kx = R[2, 1] - R[1, 2] # Oz - Ay
@@ -512,6 +513,7 @@ def slerp(q0, q1, s, shortest=False):
512513
:type shortest: bool
513514
:return: interpolated unit-quaternion
514515
:rtype: numpy.ndarray, shape=(4,)
516+
:raises ValueError: s is outside interval [0, 1]
515517
516518
An interpolated quaternion between ``q0`` when ``s`` = 0 to ``q1`` when ``s`` = 1.
517519
@@ -525,7 +527,8 @@ def slerp(q0, q1, s, shortest=False):
525527
.. warning:: There is no check that the passed values are unit-quaternions.
526528
527529
"""
528-
assert 0 <= s <= 1, 's must be in the interval [0,1]'
530+
if not 0 <= s <= 1:
531+
raise ValueError("s must be in the interval [0,1]")
529532
q0 = base.getvector(q0, 4)
530533
q1 = base.getvector(q1, 4)
531534

spatialmath/base/transforms2d.py

Lines changed: 18 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -169,7 +169,7 @@ def trlog2(T, check=True, twist=False):
169169
:type twist: bool
170170
:return: logarithm
171171
:rtype: numpy.ndarray, shape=(2,2) or (3,3)
172-
:raises: ValueError
172+
:raises ValueError: bad argument
173173
174174
An efficient closed-form solution of the matrix logarithm for arguments that
175175
are SO(2) or SE(2).
@@ -223,6 +223,7 @@ def trexp2(S, theta=None, check=True):
223223
:type theta: float
224224
:return: 2x2 or 3x3 matrix exponential in SO(2) or SE(2)
225225
:rtype: numpy.ndarray, shape=(2,2) or (3,3)
226+
:raises ValueError: bad argument
226227
227228
An efficient closed-form solution of the matrix exponential for arguments
228229
that are so(2) or se(2).
@@ -261,8 +262,8 @@ def trexp2(S, theta=None, check=True):
261262
# se(2) case
262263
if base.ismatrix(S, (3, 3)):
263264
# augmentented skew matrix
264-
if check:
265-
assert base.isskewa(S), 'argument must be a valid se(2) element'
265+
if check and not base.isskewa(S):
266+
raise ValueError("argument must be a valid se(2) element")
266267
tw = base.vexa(S)
267268
else:
268269
# 3 vector
@@ -273,8 +274,8 @@ def trexp2(S, theta=None, check=True):
273274

274275
if theta is None:
275276
(tw, theta) = base.unittwist2_norm(tw)
276-
else:
277-
assert base.isunittwist2(tw), 'If theta is specified S must be a unit twist'
277+
elif not base.isunittwist2(tw):
278+
raise ValueError("If theta is specified S must be a unit twist")
278279

279280
t = tw[0:2]
280281
w = tw[2]
@@ -290,15 +291,15 @@ def trexp2(S, theta=None, check=True):
290291
# so(2) case
291292
if base.ismatrix(S, (2, 2)):
292293
# skew symmetric matrix
293-
if check:
294-
assert base.isskew(S), 'argument must be a valid so(2) element'
294+
if check and not base.isskew(S):
295+
raise ValueError("argument must be a valid so(2) element")
295296
w = base.vex(S)
296297
else:
297298
# 1 vector
298299
w = base.getvector(S)
299300

300-
if theta is not None:
301-
assert base.isunitvec(w), 'If theta is specified S must be a unit twist'
301+
if theta is not None and not base.isunitvec(w):
302+
raise ValueError("If theta is specified S must be a unit twist")
302303

303304
# do Rodrigues' formula for rotation
304305
return base.rodrigues(w, theta)
@@ -318,6 +319,7 @@ def trinterp2(start, end, s=None):
318319
:type s: float
319320
:return: SO(2) or SE(2) matrix
320321
:rtype: np.ndarray, shape=(2,2), (3,3)
322+
:raises ValueError: bad arguments
321323
322324
- ``trinterp2(None, T, S)`` is a homogeneous transform (3x3) interpolated
323325
between identity when S=0 and T (3x3) when S=1.
@@ -346,7 +348,8 @@ def trinterp2(start, end, s=None):
346348
th = s * th0
347349
else:
348350
# TRINTERP2(T1, start= s)
349-
assert start.shape == end.shape, 'start and end matrices must be same shape'
351+
if start.shape != end.shape:
352+
raise ValueError("start and end matrices must be same shape")
350353

351354
th0 = math.atan2(start[1, 0], start[0, 0])
352355
th1 = math.atan2(end[1, 0], end[0, 0])
@@ -365,7 +368,8 @@ def trinterp2(start, end, s=None):
365368
pr = s * p0
366369
else:
367370
# TRINTERP2(T0, T1, s)
368-
assert start.shape == end.shape, 'both matrices must be same shape'
371+
if start.shape != end.shape:
372+
raise ValueError("both matrices must be same shape")
369373

370374
th0 = math.atan2(start[1, 0], start[0, 0])
371375
th1 = math.atan2(end[1, 0], end[0, 0])
@@ -493,6 +497,7 @@ def trplot2(T, axes=None, block=True, dims=None, color='blue', frame=None, # pyl
493497
:type d2: distance of frame label text from origin, default 0.05
494498
:return: axes containing the frame
495499
:rtype: AxesSubplot
500+
:raises ValueError: bad argument
496501
497502
Adds a 2D coordinate frame represented by the SO(2) or SE(2) matrix to the current axes.
498503
@@ -514,8 +519,8 @@ def trplot2(T, axes=None, block=True, dims=None, color='blue', frame=None, # pyl
514519
# check input types
515520
if isrot2(T, check=True):
516521
T = base.r2t(T)
517-
else:
518-
assert ishom2(T, check=True)
522+
elif not ishom2(T, check=True):
523+
raise ValueError("argument is not valid SE(2) matrix")
519524

520525
if axes is None:
521526
# create an axes

0 commit comments

Comments
 (0)
0