@@ -1216,7 +1216,7 @@ def _getlink(self, link, default=None):
12161216 else :
12171217 raise TypeError ('unknown argument' )
12181218
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 ):
12201220 r"""
12211221 Manipulator geometric Jacobian in the base frame
12221222
@@ -1227,9 +1227,9 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
12271227 :type end: str or ELink or Gripper
12281228 :param start: the link considered as the base frame, defaults to the robots's base frame
12291229 :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
12311231 end of end, defaults to None
1232- :type offset : SE3, optional
1232+ :type tool : SE3, optional
12331233 :param T: The transformation matrix of the reference point which the
12341234 Jacobian represents with respect to the base frame. Use this to
12351235 avoid caluclating forward kinematics to save time, defaults
@@ -1262,16 +1262,16 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
12621262 with ``start`` closest to the base.
12631263 """ # noqa
12641264
1265- if offset is None :
1266- offset = SE3 ()
1265+ if tool is None :
1266+ tool = SE3 ()
12671267
12681268 path , n = self .get_path (end , start )
12691269
12701270 q = getvector (q , self .n )
12711271
12721272 if T is None :
12731273 T = self .base .inv () * \
1274- self .fkine (q , end = end , start = start ) * offset
1274+ self .fkine (q , end = end , start = start ) * tool
12751275 T = T .A
12761276 U = np .eye (4 )
12771277 j = 0
@@ -1283,7 +1283,7 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
12831283 U = U @ link .A (q [link .jindex ], fast = True )
12841284
12851285 if link == end :
1286- U = U @ offset .A
1286+ U = U @ tool .A
12871287
12881288 Tu = np .linalg .inv (U ) @ T
12891289 n = U [:3 , 0 ]
@@ -1323,7 +1323,7 @@ def jacob0(self, q, end=None, start=None, offset=None, T=None):
13231323
13241324 return J
13251325
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 ):
13271327 r"""
13281328 Manipulator geometric Jacobian in the end-effector frame
13291329
@@ -1334,9 +1334,9 @@ def jacobe(self, q, end=None, start=None, offset=None, T=None):
13341334 :type end: str or ELink or Gripper
13351335 :param start: the link considered as the base frame, defaults to the robots's base frame
13361336 :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
13381338 end of end, defaults to None
1339- :type offset : SE3, optional
1339+ :type tool : SE3, optional
13401340 :param T: The transformation matrix of the reference point which the
13411341 Jacobian represents with respect to the base frame. Use this to
13421342 avoid caluclating forward kinematics to save time, defaults
@@ -1371,19 +1371,17 @@ def jacobe(self, q, end=None, start=None, offset=None, T=None):
13711371
13721372 q = getvector (q , self .n )
13731373
1374- if offset is None :
1375- offset = SE3 ()
1374+ if tool is None :
1375+ tool = SE3 ()
13761376
13771377 end , start , _ = self ._get_limit_links (end , start )
13781378
1379- # path, n = self.get_path(end, start)
1380-
13811379 if T is None :
13821380 T = self .base .inv () * \
1383- self .fkine (q , end = end , start = start ) * offset
1381+ self .fkine (q , end = end , start = start ) * tool
13841382
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
13871385 return Je
13881386
13891387 def partial_fkine0 (self , q , n , J0 = None , end = None , start = None ):
@@ -1574,7 +1572,7 @@ def cross(a, b):
15741572
15751573 if J0 is None :
15761574 q = getvector (q , n )
1577- J0 = self .jacob0 (q , end = end )
1575+ J0 = self .jacob0 (q , end = end , start = start )
15781576 else :
15791577 verifymatrix (J0 , (6 , n ))
15801578
@@ -1710,7 +1708,7 @@ def recurse(link, indent=0):
17101708
17111709 def jacobev (
17121710 self , q , end = None , start = None ,
1713- offset = None , T = None ):
1711+ tool = None , T = None ):
17141712 """
17151713 Jv = jacobev(q) is the spatial velocity Jacobian, at joint
17161714 configuration q, which relates the velocity in the base frame to the
@@ -1722,9 +1720,9 @@ def jacobev(
17221720 :type end: str or ELink or Gripper
17231721 :param start: the first link which the Jacobian represents
17241722 :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
17261724 end of end, defaults to None
1727- :type offset : SE3, optional
1725+ :type tool : SE3, optional
17281726 :param T: The transformation matrix of the reference point which the
17291727 Jacobian represents with respect to the base frame. Use this to
17301728 avoid caluclating forward kinematics to save time, defaults
@@ -1741,8 +1739,8 @@ def jacobev(
17411739 if T is None :
17421740 T = self .base .inv () * \
17431741 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
17461744 R = (T .R ).T
17471745
17481746 Jv = np .zeros ((6 , 6 ))
@@ -1753,7 +1751,7 @@ def jacobev(
17531751
17541752 def jacob0v (
17551753 self , q , end = None , start = None ,
1756- offset = None , T = None ):
1754+ tool = None , T = None ):
17571755 """
17581756 Jv = jacob0v(q) is the spatial velocity Jacobian, at joint
17591757 configuration q, which relates the velocity in the end-effector frame
@@ -1765,9 +1763,9 @@ def jacob0v(
17651763 :type end: str or ELink or Gripper
17661764 :param start: the first link which the Jacobian represents
17671765 :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
17691767 end of end, defaults to None
1770- :type offset : SE3, optional
1768+ :type tool : SE3, optional
17711769 :param T: The transformation matrix of the reference point which the
17721770 Jacobian represents with respect to the base frame. Use this to
17731771 avoid caluclating forward kinematics to save time, defaults
@@ -1784,8 +1782,8 @@ def jacob0v(
17841782 if T is None :
17851783 T = self .base .inv () * \
17861784 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
17891787 R = (T .R )
17901788
17911789 Jv = np .zeros ((6 , 6 ))
0 commit comments