8000 consistently import spatialmath.base as smb · rocsys/spatialmath-python@35d8ce5 · GitHub
[go: up one dir, main page]

Skip to content

Commit 35d8ce5

Browse files
committed
consistently import spatialmath.base as smb
1 parent 95361cf commit 35d8ce5

File tree

6 files changed

+364
-368
lines changed

6 files changed

+364
-368
lines changed

spatialmath/baseposematrix.py

Lines changed: 41 additions & 43 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 smbase
17+
import spatialmath.base as smb
1818
from spatialmath.base.types import *
1919
from 10000 spatialmath.baseposelist import BasePoseList
2020

@@ -369,9 +369,9 @@ def log(self, twist: Optional[bool] = False) -> Union[NDArray, List[NDArray]]:
369369
:SymPy: not supported
370370
"""
371371
if self.N == 2:
372-
log = [smbase.trlog2(x, twist=twist) for x in self.data]
372+
log = [smb.trlog2(x, twist=twist) for x in self.data]
373373
else:
374-
log = [smbase.trlog(x, twist=twist) for x in self.data]
374+
log = [smb.trlog(x, twist=twist) for x in self.data]
375375
if len(log) == 1:
376376
return log[0]
377377
else:
@@ -418,7 +418,7 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel
418418
if isinstance(s, int) and s > 1:
419419
s = np.linspace(0, 1, s)
420420
else:
421-
s = smbase.getvector(s)
421+
s = smb.getvector(s)
422422
s = np.clip(s, 0, 1)
423423

424424
if len(self) > 1:
@@ -432,13 +432,13 @@ def interp(self, end: Optional[bool] = None, s: Union[int, float] = None) -> Sel
432432
if self.N == 2:
433433
# SO(2) or SE(2)
434434
return self.__class__(
435-
[smbase.trinterp2(start=self.A, end=end, s=_s) for _s in s]
435+
[smb.trinterp2(start=self.A, end=end, s=_s) for _s in s]
436436
)
437437

438438
elif self.N == 3:
439439
# SO(3) or SE(3)
440440
return self.__class__(
441-
[smbase.trinterp(start=self.A, end=end, s=_s) for _s in s]
441+
[smb.trinterp(start=self.A, end=end, s=_s) for _s in s]
442442
)
443443

444444
def interp1(self, s: float = None) -> Self:
@@ -488,32 +488,30 @@ def interp1(self, s: float = None) -> Self:
488488
489489
#. For SO3 and SE3 rotation is interpolated using quaternion spherical linear interpolation (slerp).
490490
491-
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.smbase.transforms2d.trinterp2`
491+
:seealso: :func:`interp`, :func:`~spatialmath.base.transforms3d.trinterp`, :func:`~spatialmath.base.quaternions.qslerp`, :func:`~spatialmath.smb.transforms2d.trinterp2`
492492
493493
:SymPy: not supported
494494
"""
495-
s = smbase.getvector(s)
495+
s = smb.getvector(s)
496496
s = np.clip(s, 0, 1)
497497

498498
if self.N == 2:
499499
# SO(2) or SE(2)
500500
if len(s) > 1:
501501
assert len(self) == 1, "if len(s) > 1, len(X) must == 1"
502-
return self.__class__(
503-
[smbase.trinterp2(start, self.A, s=_s) for _s in s]
504-
)
502+
return self.__class__([smb.trinterp2(start, self.A, s=_s) for _s in s])
505503
else:
506504
return self.__class__(
507-
[smbase.trinterp2(start, x, s=s[0]) for x in self.data]
505+
[smb.trinterp2(start, x, s=s[0]) for x in self.data]
508506
)
509507
elif self.N == 3:
510508
# SO(3) or SE(3)
511509
if len(s) > 1:
512510
assert len(self) == 1, "if len(s) > 1, len(X) must == 1"
513-
return self.__class__([smbase.trinterp(None, self.A, s=_s) for _s in s])
511+
return self.__class__([smb.trinterp(None, self.A, s=_s) for _s in s])
514512
else:
515513
return self.__class__(
516-
[smbase.trinterp(None, x, s=s[0]) for x in self.data]
514+
[smb.trinterp(None, x, s=s[0]) for x in self.data]
517515
)
518516

519517
def norm(self) -> Self:
@@ -546,9 +544,9 @@ def norm(self) -> Self:
546544
:seealso: :func:`~spatialmath.base.transforms3d.trnorm`, :func:`~spatialmath.base.transforms2d.trnorm2`
547545
"""
548546
if self.N == 2:
549-
return self.__class__([smbase.trnorm2(x) for x in self.data])
547+
return self.__class__([smb.trnorm2(x) for x in self.data])
550548
else:
551-
return self.__class__([smbase.trnorm(x) for x in self.data])
549+
return self.__class__([smb.trnorm(x) for x in self.data])
552550

553551
def simplify(self) -> Self:
554552
"""
@@ -580,7 +578,7 @@ def simplify(self) -> Self:
580578
:SymPy: supported
581579
"""
582580

583-
vf = np.vectorize(smbase.sym.simplify)
581+
vf = np.vectorize(smb.sym.simplify)
584582
return self.__class__([vf(x) for x in self.data], check=False)
585583

586584
def stack(self) -> NDArray:
@@ -682,10 +680,10 @@ def printline(self, *args, **kwargs) -> None:
682680
"""
683681
if self.N == 2:
684682
for x in self.data:
685-
smbase.trprint2(x, *args, **kwargs)
683+
smb.trprint2(x, *args, **kwargs)
686684
else:
687685
for x in self.data:
688-
smbase.trprint(x, *args, **kwargs)
686+
smb.trprint(x, *args, **kwargs)
689687

690688
def strline(self, *args, **kwargs) -> str:
691689
"""
@@ -744,10 +742,10 @@ def strline(self, *args, **kwargs) -> str:
744742
s = ""
745743
if self.N == 2:
746744
for x in self.data:
747-
s += smbase.trprint2(x, *args, file=False, **kwargs)
745+
s += smb.trprint2(x, *args, file=False, **kwargs)
748746
else:
749747
for x in self.data:
750-
s += smbase.trprint(x, *args, file=False, **kwargs)
748+
s += smb.trprint(x, *args, file=False, **kwargs)
751749
return s
752750

753751
def __repr__(self) -> str:
@@ -773,7 +771,7 @@ def trim(x):
773771
if x.dtype == "O":
774772
return x
775773
else:
776-
return smbase.removesmall(x)
774+
return smb.removesmall(x)
777775

778776
name = type(self).__name__
779777
if len(self) == 0:
@@ -901,7 +899,7 @@ def mformat(self, X):
901899
rowstr = " "
902900
# format the columns
903901
for colnum, element in enumerate(row):
904-
if smbase.sym.issymbol(element):
902+
if smb.sym.issymbol(element):
905903
s = "{:<12s}".format(str(element))
906904
else:
907905
if (
@@ -971,9 +969,9 @@ def plot(self, *args, **kwargs) -> None:
971969
:seealso: :func:`~spatialmath.base.transforms3d.trplot`, :func:`~spatialmath.base.transforms2d.trplot2`
972970
"""
973971
if self.N == 2:
974-
smbase.trplot2(self.A, *args, **kwargs)
972+
smb.trplot2(self.A, *args, **kwargs)
975973
else:
976-
smbase.trplot(self.A, *args, **kwargs)
974+
smb.trplot(self.A, *args, **kwargs)
977975

978976
def animate(self, *args, start=None, **kwargs) -> None:
979977
"""
@@ -1004,15 +1002,15 @@ def animate(self, *args, start=None, **kwargs) -> None:
10041002
if len(self) > 1:
10051003
# trajectory case
10061004
if self.N == 2:
1007-
smbase.tranimate2(self.data, *args, **kwargs)
1005+
smb.tranimate2(self.data, *args, **kwargs)
10081006
else:
1009-
smbase.tranimate(self.data, *args, **kwargs)
1007+
smb.tranimate(self.data, *args, **kwargs)
10101008
else:
10111009
# singleton case
10121010
if self.N == 2:
1013-
smbase.tranimate2(self.A, start=start, *args, **kwargs)
1011+
smb.tranimate2(self.A, start=start, *args, **kwargs)
10141012
else:
1015-
smbase.tranimate(self.A, start=start, *args, **kwargs)
1013+
smb.tranimate(self.A, start=start, *args, **kwargs)
10161014

10171015
# ------------------------------------------------------------------------ #
10181016
def prod(self) -> Self:
@@ -1157,13 +1155,13 @@ def __mul__(left, right): # pylint: disable=no-self-argument
11571155
elif isinstance(right, (list, tuple, np.ndarray)):
11581156
# print('*: pose x array')
11591157
if len(left) == 1:
1160-
if smbase.isvector(right, left.N):
1158+
if smb.isvector(right, left.N):
11611159
# pose x vector
11621160
# print('*: pose x vector')
1163-
v = smbase.getvector(right, out="col")
1161+
v = smb.getvector(right, out="col")
11641162
if left.isSE:
11651163
# SE(n) x vector
1166-
return smbase.h2e(left.A @ smbase.e2h(v))
1164+
return smb.h2e(left.A @ smb.e2h(v))
11671165
else:
11681166
# SO(n) x vector
11691167
return left.A @ v
@@ -1173,19 +1171,19 @@ def __mul__(left, right): # pylint: disable=no-self-argument
11731171
else:
11741172
if left.isSE:
11751173
# SE(n) x [set of vectors]
1176-
return smbase.h2e(left.A @ smbase.e2h(right))
1174+
return smb.h2e(left.A @ smb.e2h(right))
11771175
else:
11781176
# SO(n) x [set of vectors]
11791177
return left.A @ right
11801178

1181-
elif len(left) > 1 and smbase.isvector(right, left.N):
1179+
elif len(left) > 1 and smb.isvector(right, left.N):
11821180
# pose array x vector
11831181
# print('*: pose array x vector')
1184-
v = smbase.getvector(right)
1182+
v = smb.getvector(right)
11851183
if left.isSE:
11861184
# SE(n) x vector
1187-
v = smbase.e2h(v)
1188-
return np.array([smbase.h2e(x @ v).flatten() for x in left.A]).T
1185+
v = smb.e2h(v)
1186+
return np.array([smb.h2e(x @ v).flatten() for x in left.A]).T
11891187
else:
11901188
# SO(n) x vector
11911189
return np.array([(x @ v).flatten() for x in left.A]).T
@@ -1205,7 +1203,7 @@ def __mul__(left, right): # pylint: disable=no-self-argument
12051203
and right.shape[0] == left.N
12061204
):
12071205
# SE(n) x matrix
1208-
return smbase.h2e(left.A @ smbase.e2h(right))
1206+
return smb.h2e(left.A @ smb.e2h(right))
12091207
elif (
12101208
isinstance(right, np.ndarray)
12111209
and left.isSO
@@ -1222,11 +1220,11 @@ def __mul__(left, right): # pylint: disable=no-self-argument
12221220
):
12231221
# SE(n) x matrix
12241222
return np.c_[
1225-
[smbase.h2e(x.A @ smbase.e2h(y)) for x, y in zip(right, left.T)]
1223+
[smb.h2e(x.A @ smb.e2h(y)) for x, y in zip(right, left.T)]
12261224
].T
12271225
else:
12281226
raise ValueError("bad operands")
1229-
elif smbase.isscalar(right):
1227+
elif smb.isscalar(right):
12301228
return left._op2(right, lambda x, y: x * y)
12311229
else:
12321230
return NotImplemented
@@ -1252,7 +1250,7 @@ def __matmul__(left, right): # pylint: disable=no-self-argument
12521250
if isinstance(left, right.__class__):
12531251
# print('*: pose x pose')
12541252
return left.__class__(
1255-
left._op2(right, lambda x, y: smbase.trnorm(x @ y)), check=False
1253+
left._op2(right, lambda x, y: smb.trnorm(x @ y)), check=False
12561254
)
12571255
else:
12581256
raise TypeError("@ only applies to pose composition")
@@ -1346,7 +1344,7 @@ def __truediv__(left, right): # pylint: disable=no-self-argument
13461344
return left.__class__(
13471345
left._op2(right.inv(), lambda x, y: x @ y), check=False
13481346
)
1349-
elif smbase.isscalar(right):
1347+
elif smb.isscalar(right):
13501348
return left._op2(right, lambda x, y: x / y)
13511349
else:
13521350
raise ValueError("bad operands")
@@ -1637,7 +1635,7 @@ def _op2(left, right: Self, op: Callable): # pylint: disable=no-self-argument
16371635
return [op(x, y) for (x, y) in zip(left.A, right.A)]
16381636
else:
16391637
raise ValueError("length of lists to == must be same length")
1640-
elif smbase.isscalar(right) or (
1638+
elif smb.isscalar(right) or (
16411639
isinstance(right, np.ndarray) and right.shape == left.shape
16421640
):
16431641
# class by matrix

0 commit comments

Comments
 (0)
0