3
3
4
4
# import matplotlib.pyplot as plt
5
5
import time
6
- from spatialmath import base , SE3
6
+ from spatialmath import SE3
7
+ import spatialmath .base as smb
7
8
8
9
from bdsim .components import TransferBlock , FunctionBlock , SourceBlock
9
10
from bdsim .graphics import GraphicsBlock
@@ -490,8 +491,8 @@ def __init__(self, q0, qf, qd0=None, qdf=None, T=None, **blockargs):
490
491
)
491
492
)
492
493
493
- q0 = base .getvector (q0 )
494
- qf = base .getvector (qf )
494
+ q0 = smb .getvector (q0 )
495
+ qf = smb .getvector (qf )
495
496
496
497
if not len (q0 ) == len (qf ):
497
498
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
912
913
913
914
super ().__init__ (nin = nin , blockclass = blockclass , ** blockargs )
914
915
915
- y0 = base .getvector (y0 )
916
- yf = base .getvector (yf )
916
+ y0 = smb .getvector (y0 )
917
+ yf = smb .getvector (yf )
917
918
assert len (y0 ) == len (yf ), "y0 and yf must have same length"
918
919
919
920
self .y0 = y0
@@ -1389,7 +1390,7 @@ def __init__(self, robot, q0=None, **blockargs):
1389
1390
if q0 is None :
1390
1391
q0 = np .zeros ((robot .n ,))
1391
1392
else :
1392
- q0 = base .getvector (q0 , robot .n )
1393
+ q0 = smb .getvector (q0 , robot .n )
1393
1394
self ._x0 = np .r_ [q0 , np .zeros ((robot .n ,))]
1394
1395
self ._qdd = None
1395
1396
@@ -1474,8 +1475,15 @@ def __init__(
1474
1475
"""
1475
1476
:param robot: Robot model
1476
1477
: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
+
1479
1487
:param blockargs: |BlockOptions|
1480
1488
:type blockargs: dict
1481
1489
"""
@@ -1499,7 +1507,7 @@ def __init__(
1499
1507
if q0 is None :
1500
1508
q0 = np .zeros ((robot .n ,))
1501
1509
else :
1502
- q0 = base .getvector (q0 , robot .n )
1510
+ q0 = smb .getvector (q0 , robot .n )
1503
1511
# append qd0, assumed to be zero
1504
1512
self ._x0 = np .r_ [q0 , np .zeros ((robot .n ,))]
1505
1513
self ._qdd = None
@@ -1511,7 +1519,7 @@ def output(self, t, inports, x):
1511
1519
qdd = self ._qdd # from last deriv
1512
1520
1513
1521
T = self .robot .fkine (q )
1514
- x = base .tr2x (T .A )
1522
+ x = smb .tr2x (T .A )
1515
1523
1516
1524
Ja = self .robot .jacob0_analytical (q , self .representation )
1517
1525
xd = Ja @ qd
@@ -1524,7 +1532,7 @@ def output(self, t, inports, x):
1524
1532
if qdd is None :
1525
1533
xdd = None
1526
1534
else :
1527
- Ja_dot = self .robot .jacob_dot (q , qd , J0 = Ja )
1535
+ Ja_dot = self .robot .jacob0_dot (q , qd , J0 = Ja )
1528
1536
xdd = Ja @ qdd + Ja_dot @ qd
1529
1537
1530
1538
return [q , qd , x , xd , xdd ]
0 commit comments