@@ -748,8 +748,8 @@ def _get_limit_links(self, end=None, start=None):
748
748
"""
749
749
750
750
# Try cache
751
- if self ._cache_end is not None :
752
- return self ._cache_end , self ._cache_start , self ._cache_end_tool
751
+ # if self._cache_end is not None:
752
+ # return self._cache_end, self._cache_start, self._cache_end_tool
753
753
754
754
tool = None
755
755
if end is None :
@@ -903,8 +903,8 @@ def URDF(cls, file_path, gripper=None):
903
903
Construct an ERobot object from URDF file
904
904
:param file_path: [description]
905
905
:type file_path: [type]
906
- :param gripper: index or name of the gripper link
907
- :type gripper: int or str
906
+ :param gripper: index or name of the gripper link(s)
907
+ :type gripper: int or str or list
908
908
:return: [description]
909
909
:rtype: [type]
910
910
If ``gripper`` is specified, links from that link outward are removed
@@ -925,7 +925,9 @@ def URDF(cls, file_path, gripper=None):
925
925
else :
926
926
raise TypeError ('bad argument passed as gripper' )
927
927
928
- return cls (links , name = name , gripper = gripper )
928
+ links , name = ERobot .URDF_read (file_path )
929
+
930
+ return cls (links , name = name , gripper_links = gripper )
929
931
930
932
def _reset_cache (self ):
931
933
self ._path_cache = {}
@@ -1129,7 +1131,8 @@ def fkine(
1129
1131
T = SE3 .Empty ()
1130
1132
1131
1133
for k , qk in enumerate (q ):
1132
- qk = self .toradians (qk )
1134
+ if unit == 'deg' :
1135
+ qk = self .toradians (qk )
1133
1136
link = end # start with last link
1134
1137
1135
1138
# add tool if provided
@@ -2002,9 +2005,9 @@ def jacob0(self, q):
2002
2005
def jacobe (self , q ):
2003
2006
return self .ets ().jacobe (q )
2004
2007
2005
- def fkine (self , q , unit = 'rad' ):
2008
+ def fkine (self , q , unit = 'rad' , end = None , start = None ):
2006
2009
2007
- return self .ets ().eval (q , unit = unit )
2010
+ return self .ets (start , end ).eval (q , unit = unit )
2008
2011
# --------------------------------------------------------------------- #
2009
2012
2010
2013
def plot (
@@ -2189,6 +2192,7 @@ def teach(
2189
2192
return env
2190
2193
2191
2194
2195
+
2192
2196
if __name__ == "__main__" : # pragma nocover
2193
2197
2194
2198
# import roboticstoolbox as rtb
0 commit comments