@@ -1216,7 +1216,7 @@ def _getlink(self, link, default=None):
1216
1216
else :
1217
1217
raise TypeError ('unknown argument' )
1218
1218
1219
- def jacob0 (self , q , end = None , start = None , offset = None , T = None ):
1219
+ def jacob0 (self , q , end = None , start = None , tool = None , T = None ):
1220
1220
r"""
1221
1221
Manipulator geometric Jacobian in the base frame
1222
1222
@@ -1227,9 +1227,9 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
1227
1227
:type end: str or ELink or Gripper
1228
1228
:param start: the link considered as the base frame, defaults to the robots's base frame
1229
1229
:type start: str or ELink
1230
- :param offset : a static offset transformation matrix to apply to the
1230
+ :param tool : a static tool transformation matrix to apply to the
1231
1231
end of end, defaults to None
1232
- :type offset : SE3, optional
1232
+ :type tool : SE3, optional
1233
1233
:param T: The transformation matrix of the reference point which the
1234
1234
Jacobian represents with respect to the base frame. Use this to
1235
1235
avoid caluclating forward kinematics to save time, defaults
@@ -1262,16 +1262,16 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
1262
1262
with ``start`` closest to the base.
1263
1263
""" # noqa
1264
1264
1265
- if offset is None :
1266
- offset = SE3 ()
1265
+ if tool is None :
1266
+ tool = SE3 ()
1267
1267
1268
1268
path , n = self .get_path (end , start )
1269
1269
1270
1270
q = getvector (q , self .n )
1271
1271
1272
1272
if T is None :
1273
1273
T = self .base .inv () * \
1274
- self .fkine (q , end = end , start = start ) * offset
1274
+ self .fkine (q , end = end , start = start ) * tool
1275
1275
T = T .A
1276
1276
U = np .eye (4 )
1277
1277
j = 0
@@ -1283,7 +1283,7 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
1283
1283
U = U @ link .A (q [link .jindex ], fast = True )
1284
1284
1285
1285
if link == end :
1286
- U = U @ offset .A
1286
+ U = U @ tool .A
1287
1287
1288
1288
Tu = np .linalg .inv (U ) @ T
1289
1289
n = U [:3 , 0 ]
@@ -1323,7 +1323,7 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
1323
1323
1324
1324
return J
1325
1325
1326
- def jacobe (self , q , end = None , start = None , offset = None , T = None ):
1326
+ def jacobe (self , q , end = None , start = None , tool = None , T = None ):
1327
1327
r"""
1328
1328
Manipulator geometric Jacobian in the end-effector frame
1329
1329
@@ -1334,9 +1334,9 @@ def jacobe(self, q, end=None, start=None, offset=None, T=None):
1334
1334
:type end: str or ELink or Gripper
1335
1335
:param start: the link considered as the base frame, defaults to the robots's base frame
1336
1336
:type start: str or ELink
1337
- :param offset : a static offset transformation matrix to apply to the
1337
+ :param tool : a static tool transformation matrix to apply to the
1338
1338
end of end, defaults to None
1339
- :type offset : SE3, optional
1339
+ :type tool : SE3, optional
1340
1340
:param T: The transformation matrix of the reference point which the
1341
1341
Jacobian represents with respect to the base frame. Use this to
1342
1342
avoid caluclating forward kinematics to save time, defaults
@@ -1371,19 +1371,17 @@ def jacobe(self, q, end=None, start=None, offset=None, T=None):
1371
1371
1372
1372
q = getvector (q , self .n )
1373
1373
1374
- if offset is None :
1375
- offset = SE3 ()
1374
+ if tool is None :
1375
+ tool = SE3 ()
1376
1376
1377
1377
end , start , _ = self ._get_limit_links (end , start )
1378
1378
1379
- # path, n = self.get_path(end, start)
1380
-
1381
1379
if T is None :
1382
1380
T = self .base .inv () * \
1383
- self .fkine (q , end = end , start = start ) * offset
1381
+ self .fkine (q , end = end , start = start ) * tool
1384
1382
1385
- J0 = self .jacob0 (q , end , start , offset , T )
1386
- Je = self .jacobev (q , end , start , offset , T ) @ J0
1383
+ J0 = self .jacob0 (q , end , start , tool , T )
1384
+ Je = self .jacobev (q , end , start , tool , T ) @ J0
1387
1385
return Je
1388
1386
1389
1387
def partial_fkine0 (self , q , n , J0 = None , end = None , start = None ):
@@ -1574,7 +1572,7 @@ def cross(a, b):
1574
1572
1575
1573
if J0 is None :
1576
1574
q = getvector (q , n )
1577
- J0 = self .jacob0 (q , end = end )
1575
+ J0 = self .jacob0 (q , end = end , start = start )
1578
1576
else :
1579
1577
verifymatrix (J0 , (6 , n ))
1580
1578
@@ -1710,7 +1708,7 @@ def recurse(link, indent=0):
1710
1708
1711
1709
def jacobev (
1712
1710
self , q , end = None , start = None ,
1713
- offset = None , T = None ):
1711
+ tool = None , T = None ):
1714
1712
"""
1715
1713
Jv = jacobev(q) is the spatial velocity Jacobian, at joint
1716
1714
configuration q, which relates the velocity in the base frame to the
@@ -1722,9 +1720,9 @@ def jacobev(
1722
1720
:type end: str or ELink or Gripper
1723
1721
:param start: the first link which the Jacobian represents
1724
1722
:type start: str or ELink
1725
- :param offset : a static offset transformation matrix to apply to the
1723
+ :param tool : a static tool transformation matrix to apply to the
1726
1724
end of end, defaults to None
1727
- :type offset : SE3, optional
1725
+ :type tool : SE3, optional
1728
1726
:param T: The transformation matrix of the reference point which the
1729
1727
Jacobian represents with respect to the base frame. Use this to
1730
1728
avoid caluclating forward kinematics to save time, defaults
@@ -1741,8 +1739,8 @@ def jacobev(
1741
1739
if T is None :
1742
1740
T = self .base .inv () * \
1743
1741
self .fkine (q , end = end , start = start )
1744
- if offset is not None :
1745
- T *= offset
1742
+ if tool is not None :
1743
+ T *= tool
1746
1744
R = (T .R ).T
1747
1745
1748
1746
Jv = np .zeros ((6 , 6 ))
@@ -1753,7 +1751,7 @@ def jacobev(
1753
1751
1754
1752
def jacob0v (
1755
1753
self , q , end = None , start = None ,
1756
- offset = None , T = None ):
1754
+ tool = None , T = None ):
1757
1755
"""
1758
1756
Jv = jacob0v(q) is the spatial velocity Jacobian, at joint
1759
1757
configuration q, which relates the velocity in the end-effector frame
@@ -1765,9 +1763,9 @@ def jacob0v(
1765
1763
:type end: str or ELink or Gripper
1766
1764
:param start: the first link which the Jacobian represents
1767
1765
:type start: str or ELink
1768
- :param offset : a static offset transformation matrix to apply to the
1766
+ :param tool : a static tool transformation matrix to apply to the
1769
1767
end of end, defaults to None
1770
- :type offset : SE3, optional
1768
+ :type tool : SE3, optional
1771
1769
:param T: The transformation matrix of the reference point which the
1772
1770
Jacobian represents with respect to the base frame. Use this to
1773
1771
avoid caluclating forward kinematics to save time, defaults
@@ -1784,8 +1782,8 @@ def jacob0v(
1784
1782
if T is None :
1785
1783
T = self .base .inv () * \
1786
1784
self .fkine (q , end = end , start = start )
1787
- if offset is not None :
1788
- T *= offset
1785
+ if tool is not None :
1786
+ T *= tool
1789
1787
R = (T .R )
1790
1788
1791
1789
Jv = np .zeros ((6 , 6 ))
0 commit comments