Skip to content

Commit fe3946d

Browse files
committed
use smb instead of base
1 parent 6fb9a67 commit fe3946d

File tree

3 files changed

+22
-14
lines changed

3 files changed

+22
-14
lines changed

roboticstoolbox/blocks/arm.py

Lines changed: 19 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,8 @@
33

44
# import matplotlib.pyplot as plt
55
import time
6-
from spatialmath import base, SE3
6+
from spatialmath import SE3
7+
import spatialmath.base as smb
78

89
from bdsim.components import TransferBlock, FunctionBlock, SourceBlock
910
from bdsim.graphics import GraphicsBlock
@@ -490,8 +491,8 @@ def __init__(self, q0, qf, qd0=None, qdf=None, T=None, **blockargs):
490491
)
491492
)
492493

493-
q0 = base.getvector(q0)
494-
qf = base.getvector(qf)
494+
q0 = smb.getvector(q0)
495+
qf = smb.getvector(qf)
495496

496497
if not len(q0) == len(qf):
497498
raise ValueError("q0 and q1 must be same size")
@@ -912,8 +913,8 @@ def __init__(self, y0=0, yf=1, T=None, time=False, traj="trapezoidal", **blockar
912913

913914
super().__init__(nin=nin, blockclass=blockclass, **blockargs)
914915

915-
y0 = base.getvector(y0)
916-
yf = base.getvector(yf)
916+
y0 = smb.getvector(y0)
917+
yf = smb.getvector(yf)
917918
assert len(y0) == len(yf), "y0 and yf must have same length"
918919

919920
self.y0 = y0
@@ -1389,7 +1390,7 @@ def __init__(self, robot, q0=None, **blockargs):
13891390
if q0 is None:
13901391
q0 = np.zeros((robot.n,))
13911392
else:
1392-
q0 = base.getvector(q0, robot.n)
1393+
q0 = smb.getvector(q0, robot.n)
13931394
self._x0 = np.r_[q0, np.zeros((robot.n,))]
13941395
self._qdd = None
13951396

@@ -1474,8 +1475,15 @@ def __init__(
14741475
"""
14751476
:param robot: Robot model
14761477
:type robot: Robot subclass
1477-
:param end: Link to compute pose of, defaults to end-effector
1478-
:type end: Link or str
1478+
:param q0: Initial joint configuration
1479+
:type q0: array_like(n)
1480+
:param gravcomp: perform gravity compensation
1481+
:type gravcomp: bool
1482+
:param velcomp: perform velocity term compensation
1483+
:type velcomp: bool
1484+
:param representation: task-space representation, defaults to "rpy/xyz"
1485+
:type represenstation: str
1486+
14791487
:param blockargs: |BlockOptions|
14801488
:type blockargs: dict
14811489
"""
@@ -1499,7 +1507,7 @@ def __init__(
14991507
if q0 is None:
15001508
q0 = np.zeros((robot.n,))
15011509
else:
1502-
q0 = base.getvector(q0, robot.n)
1510+
q0 = smb.getvector(q0, robot.n)
15031511
# append qd0, assumed to be zero
15041512
self._x0 = np.r_[q0, np.zeros((robot.n,))]
15051513
self._qdd = None
@@ -1511,7 +1519,7 @@ def output(self, t, inports, x):
15111519
qdd = self._qdd # from last deriv
15121520

15131521
T = self.robot.fkine(q)
1514-
x = base.tr2x(T.A)
1522+
x = smb.tr2x(T.A)
15151523

15161524
Ja = self.robot.jacob0_analytical(q, self.representation)
15171525
xd = Ja @ qd
@@ -1524,7 +1532,7 @@ def output(self, t, inports, x):
15241532
if qdd is None:
15251533
xdd = None
15261534
else:
1527-
Ja_dot = self.robot.jacob_dot(q, qd, J0=Ja)
1535+
Ja_dot = self.robot.jacob0_dot(q, qd, J0=Ja)
15281536
xdd = Ja @ qdd + Ja_dot @ qd
15291537

15301538
return [q, qd, x, xd, xdd]

roboticstoolbox/blocks/mobile.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@
99
from bdsim.components import TransferBlock
1010
from bdsim.graphics import GraphicsBlock
1111

12-
from spatialmath import base
1312
from roboticstoolbox import mobile
1413

1514
# ------------------------------------------------------------------------ #

roboticstoolbox/blocks/spatial.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,8 @@
33

44
# import matplotlib.pyplot as plt
55
import time
6-
from spatialmath import base, SE3
6+
from spatialmath import SE3
7+
import spatialmath.base as smb
78

89
from bdsim.components import TransferBlock, FunctionBlock, SourceBlock
910
from bdsim.graphics import GraphicsBlock
@@ -62,7 +63,7 @@ def __init__(self, **blockargs):
6263
self.outport_names(("$\delta$",))
6364

6465
def output(self, t, inports, x):
65-
return [base.tr2delta(inports[0].A, inports[1].A)]
66+
return [smb.tr2delta(inports[0].A, inports[1].A)]
6667

6768

6869
# ------------------------------------------------------------------------ #

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy