10000 consistently import spatialmath.base as smbase · rocsys/spatialmath-python@42a8c97 · GitHub
[go: up one dir, main page]

Skip to content

Commit 42a8c97

Browse files
committed
consistently import spatialmath.base as smbase
1 parent e3e95f9 commit 42a8c97

File tree

6 files changed

+359
-337
lines changed

6 files changed

+359
-337
lines changed

spatialmath/baseposelist.py

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,10 @@
66
from __future__ import annotations
77
from collections import UserList
88
from abc import ABC, abstractproperty, abstractstaticmethod
9+
import copy
910
import numpy as np
10-
import spatialmath.base.argcheck as argcheck
11+
from spatialmath.base.argcheck import isnumberlist, isscalar
1112
from spatialmath.base.types import *
12-
import copy
1313

1414
_numtypes = (int, np.int64, float, np.float64)
1515

@@ -207,9 +207,7 @@ def arghandler(
207207
self.data = [x.A for x in arg]
208208

209209
elif (
210-
argcheck.isnumberlist(arg)
211-
and len(self.shape) == 1
212-
and len(arg) == self.shape[0]
210+
isnumberlist(arg) and len(self.shape) == 1 and len(arg) == self.shape[0]
213211
):
214212
self.data = [np.array(arg)]
215213

@@ -561,7 +559,7 @@ def binop(
561559
# class * class
562560
if len(left) == 1:
563561
# singleton *
564-
if argcheck.isscalar(right):
562+
if isscalar(right):
565563
if list1:
566564
return [op(left._A, right)]
567565
else:
@@ -577,7 +575,7 @@ def binop(
577575
return [op(left.A, x) for x in right.A]
578576
else:
579577
# non-singleton *
580-
if argcheck.isscalar(right):
578+
if isscalar(right):
581579
return [op(x, right) for x in left.A]
582580
elif len(right) == 1:
583581
# non-singleton * singleton

spatialmath/baseposematrix.py

Lines changed: 46 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
# except ImportError: # pragma: no cover
1515
# _symbolics = False
1616

17-
import spatialmath.base as base
17+
import spatialmath.base as smbase
1818
from spatialmath.base.types import *
1919
from spatialmath.baseposelist import BasePoseList
2020

@@ -30,6 +30,9 @@
3030
except ImportError:
3131
# print('colored not found')
3232
_colored = False
33+
except AttributeError:
34+
# print('colored failed to load, can happen from MATLAB import')
35+
_colored = False
3336

3437
try:
3538
from ansitable import ANSIMatrix
@@ -366,9 +369,9 @@ def log(self, twist: Optional[bool] = False) -> Union[NDArray, List[NDArray]]:
366369
:SymPy: not supported
367370
"""
368371
if self.N == 2:
369-
log = [base.trlog2(x, twist=twist) for x in self.data]
372+
log = [smbase.trlog2(x, twist=twist) for x in self.data]
370373
else:
371-
log = [base.trlog(x, twist=twist) for x in self.data]
374+
log = [smbase.trlog(x, twist=twist) for x in self.data]
372375
if len(log) == 1:
373376
return log[0]
374377
else:
@@ -415,7 +418,7 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel
415418
if isinstance(s, int) and s > 1:
416419
s = np.linspace(0, 1, s)
417420
else:
418-
s = base.getvector(s)
421+
s = smbase.getvector(s)
419422
s = np.clip(s, 0, 1)
420423

421424
if len(self) > 1:
@@ -429,13 +432,13 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel
429432
if self.N == 2:
430433
# SO(2) or SE(2)
431434
return self.__class__(
432-
[base.trinterp2(start=self.A, end=end, s=_s) for _s in s]
435+
[smbase.trinterp2(start=self.A, end=end, s=_s) for _s in s]
433436
)
434437

435438
elif self.N == 3:
436439
# SO(3) or SE(3)
437440
return self.__class__(
438-
[base.trinterp(start=self.A, end=end, s=_s) for _s in s]
441+
[smbase.trinterp(start=self.A, end=end, s=_s) for _s in s]
439442
)
440443

441444
def interp1(self, s: float = None) -> Self:
@@ -485,30 +488,32 @@ def interp1(self, s: float = None) -> Self:
485488
486489
#. For SO3 and SE3 rotation is interpolated using quaternion spherical linear interpolation (slerp).
487490
488-
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.base.transforms2d.trinterp2`
491+
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.smbase.transforms2d.trinterp2`
489492
490493
:SymPy: not supported
491494
"""
492-
s = base.getvector(s)
495+
s = smbase.getvector(s)
493496
s = np.clip(s, 0, 1)
494497

495498
if self.N == 2:
496499
# SO(2) or SE(2)
497500
if len(s) > 1:
498501
assert len(self) == 1, "if len(s) > 1, len(X) must == 1"
499-
return self.__class__([base.trinterp2(start, self.A, s=_s) for _s in s])
502+
return self.__class__(
503+
[smbase.trinterp2(start, self.A, s=_s) for _s in s]
504+
)
500505
else:
501506
return self.__class__(
502-
[base.trinterp2(start, x, s=s[0]) for x in self.data]
507+
[smbase.trinterp2(start, x, s=s[0]) for x in self.data]
503508
)
504509
elif self.N == 3:
505510
# SO(3) or SE(3)
506511
if len(s) > 1:
507512
assert len(self) == 1, "if len(s) > 1, len(X) must == 1"
508-
return self.__class__([base.trinterp(None, self.A, s=_s) for _s in s])
513+
return self.__class__([smbase.trinterp(None, self.A, s=_s) for _s in s])
509514
else:
510515
return self.__class__(
511-
[base.trinterp(None, x, s=s[0]) for x in self.data]
516+
[smbase.trinterp(None, x, s=s[0]) for x in self.data]
512517
)
513518

514519
def norm(self) -> Self:
@@ -541,9 +546,9 @@ def norm(self) -> Self:
541546
:seealso: :func:`~spatialmath.base.transforms3d.trnorm`, :func:`~spatialmath.base.transforms2d.trnorm2`
542547
"""
543548
if self.N == 2:
544-
return self.__class__([base.trnorm2(x) for x in self.data])
549+
return self.__class__([smbase.trnorm2(x) for x in self.data])
545550
else:
546-
return self.__class__([base.trnorm(x) for x in self.data])
551+
return self.__class__([smbase.trnorm(x) for x in self.data])
547552

548553
def simplify(self) -> Self:
549554
"""
@@ -575,7 +580,7 @@ def simplify(self) -> Self:
575580
:SymPy: supported
576581
"""
577582

578-
vf = np.vectorize(base.sym.simplify)
583+
vf = np.vectorize(smbase.sym.simplify)
579584
return self.__class__([vf(x) for x in self.data], check=False)
580585

581586
def stack(self) -> NDArray:
@@ -677,10 +682,10 @@ def printline(self, *args, **kwargs) -> None:
677682
"""
678683
if self.N == 2:
679684
for x in self.data:
680-
base.trprint2(x, *args, **kwargs)
685+
smbase.trprint2(x, *args, **kwargs)
681686
else:
682687
for x in self.data:
683-
base.trprint(x, *args, **kwargs)
688+
smbase.trprint(x, *args, **kwargs)
684689

685690
def strline(self, *args, **kwargs) -> str:
686691
"""
@@ -739,10 +744,10 @@ def strline(self, *args, **kwargs) -> str:
739744
s = ""
740745
if self.N == 2:
741746
for x in self.data:
742-
s += base.trprint2(x, *args, file=False, **kwargs)
747+
s += smbase.trprint2(x, *args, file=False, **kwargs)
743748
else:
744749
for x in self.data:
745-
s += base.trprint(x, *args, file=False, **kwargs)
750+
s += smbase.trprint(x, *args, file=False, **kwargs)
746751
return s
747752

748753
def __repr__(self) -> str:
@@ -768,7 +773,7 @@ def trim(x):
768773
if x.dtype == "O":
769774
return x
770775
else:
771-
return base.removesmall(x)
776+
return smbase.removesmall(x)
772777

773778
name = type(self).__name__
774779
if len(self) == 0:
@@ -896,7 +901,7 @@ def mformat(self, X):
896901
rowstr = " "
897902
# format the columns
898903
for colnum, element in enumerate(row):
899-
if base.sym.issymbol(element):
904+
if smbase.sym.issymbol(element):
900905
s = "{:<12s}".format(str(element))
901906
else:
902907
if (
@@ -966,9 +971,9 @@ def plot(self, *args, **kwargs) -> None:
966971
:seealso: :func:`~spatialmath.base.transforms3d.trplot`, :func:`~spatialmath.base.transforms2d.trplot2`
967972
"""
968973
if self.N == 2:
969-
base.trplot2(self.A, *args, **kwargs)
974+
smbase.trplot2(self.A, *args, **kwargs)
970975
else:
971-
base.trplot(self.A, *args, **kwargs)
976+
smbase.trplot(self.A, *args, **kwargs)
972977

973978
def animate(self, *args, start=None, **kwargs) -> None:
974979
"""
@@ -999,15 +1004,15 @@ def animate(self, *args, start=None, **kwargs) -> None:
9991004
if len(self) > 1:
10001005
# trajectory case
10011006
if self.N == 2:
1002-
base.tranimate2(self.data, *args, **kwargs)
1007+
smbase.tranimate2(self.data, *args, **kwargs)
10031008
else:
1004-
base.tranimate(self.data, *args, **kwargs)
1009+
smbase.tranimate(self.data, *args, **kwargs)
10051010
else:
10061011
# singleton case
10071012
if self.N == 2:
1008-
base.tranimate2(self.A, start=start, *args, **kwargs)
1013+
smbase.tranimate2(self.A, start=start, *args, **kwargs)
10091014
else:
1010-
base.tranimate(self.A, start=start, *args, **kwargs)
1015+
smbase.tranimate(self.A, start=start, *args, **kwargs)
10111016

10121017
# ------------------------------------------------------------------------ #
10131018
def prod(self) -> Self:
@@ -1152,13 +1157,13 @@ def __mul__(left, right): # pylint: disable=no-self-argument
11521157
elif isinstance(right, (list, tuple, np.ndarray)):
11531158
# print('*: pose x array')
11541159
if len(left) == 1:
1155-
if base.isvector(right, left.N):
1160+
if smbase.isvector(right, left.N):
11561161
# pose x vector
11571162
# print('*: pose x vector')
1158-
v = base.getvector(right, out="col")
1163+
v = smbase.getvector(right, out="col")
11591164
if left.isSE:
11601165
# SE(n) x vector
1161-
return base.h2e(left.A @ base.e2h(v))
1166+
return smbase.h2e(left.A @ smbase.e2h(v))
11621167
else:
11631168
# SO(n) x vector
11641169
return left.A @ v
@@ -1168,19 +1173,19 @@ def __mul__(left, right): # pylint: disable=no-self-argument
11681173
else:
11691174
if left.isSE:
11701175
# SE(n) x [set of vectors]
1171-
return base.h2e(left.A @ base.e2h(right))
1176+
return smbase.h2e(left.A @ smbase.e2h(right))
11721177
else:
11731178
# SO(n) x [set of vectors]
11741179
return left.A @ right
11751180

1176-
elif len(left) > 1 and base.isvector(right, left.N):
1181+
elif len(left) > 1 and smbase.isvector(right, left.N):
11771182
# pose array x vector
11781183
# print('*: pose array x vector')
1179-
v = base.getvector(right)
1184+
v = smbase.getvector(right)
11801185
if left.isSE:
11811186
# SE(n) x vector
1182-
v = base.e2h(v)
1183-
return np.array([base.h2e(x @ v).flatten() for x in left.A]).T
1187+
v = smbase.e2h(v)
1188+
return np.array([smbase.h2e(x @ v).flatten() for x in left.A]).T
11841189
else:
11851190
# SO(n) x vector
11861191
return np.array([(x @ v).flatten() for x in left.A]).T
@@ -1200,7 +1205,7 @@ def __mul__(left, right): # pylint: disable=no-self-argument
12001205
and right.shape[0] == left.N
12011206
):
12021207
# SE(n) x matrix
1203-
return base.h2e(left.A @ base.e2h(right))
1208+
return smbase.h2e(left.A @ smbase.e2h(right))
12041209
elif (
12051210
isinstance(right, np.ndarray)
12061211
and left.isSO
@@ -1217,11 +1222,11 @@ def __mul__(left, right): # pylint: disable=no-self-argument
12171222
):
12181223
# SE(n) x matrix
12191224
return np.c_[
1220-
[base.h2e(x.A @ base.e2h(y)) for x, y in zip(right, left.T)]
1225+
[smbase.h2e(x.A @ smbase.e2h(y)) for x, y in zip(right, left.T)]
12211226
].T
12221227
else:
12231228
raise ValueError("bad operands")
1224-
elif base.isscalar(right):
1229+
elif smbase.isscalar(right):
12251230
return left._op2(right, lambda x, y: x * y)
12261231
else:
12271232
return NotImplemented
@@ -1247,7 +1252,7 @@ def __matmul__(left, right): # pylint: disable=no-self-argument
12471252
if isinstance(left, right.__class__):
12481253
# print('*: pose x pose')
12491254
return left.__class__(
1250-
left._op2(right, lambda x, y: base.trnorm(x @ y)), check=False
1255+
left._op2(right, lambda x, y: smbase.trnorm(x @ y)), check=False
12511256
)
12521257
else:
12531258
raise TypeError("@ only applies to pose composition")
@@ -1341,7 +1346,7 @@ def __truediv__(left, right): # pylint: disable=no-self-argument
13411346
return left.__class__(
13421347
left._op2(right.inv(), lambda x, y: x @ y), check=False
13431348
)
1344-
elif base.isscalar(right):
1349+
elif smbase.isscalar(right):
13451350
return left._op2(right, lambda x, y: x / y)
13461351
else:
13471352
raise ValueError("bad operands")
@@ -1632,7 +1637,7 @@ def _op2(left, right: Self, op: Callable): # pylint: disable=no-self-argument
16321637
return [op(x, y) for (x, y) in zip(left.A, right.A)]
16331638
else:
16341639
raise ValueError("length of lists to == must be same length")
1635-
elif base.isscalar(right) or (
1640+
elif smbase.isscalar(right) or (
16361641
isinstance(right, np.ndarray) and right.shape == left.shape
16371642
):
16381643
# class by matrix

0 commit comments

Comments
 (0)
0