Skip to content

Commit bc91f4e

Browse files
committed
degrees conversion
ERobot2 fkine
1 parent c1e023f commit bc91f4e

File tree

1 file changed

+12
-8
lines changed

1 file changed

+12
-8
lines changed

roboticstoolbox/robot/ERobot.py

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -748,8 +748,8 @@ def _get_limit_links(self, end=None, start=None):
748748
"""
749749

750750
# 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
753753

754754
tool = None
755755
if end is None:
@@ -903,8 +903,8 @@ def URDF(cls, file_path, gripper=None):
903903
Construct an ERobot object from URDF file
904904
:param file_path: [description]
905905
: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
908908
:return: [description]
909909
:rtype: [type]
910910
If ``gripper`` is specified, links from that link outward are removed
@@ -925,7 +925,9 @@ def URDF(cls, file_path, gripper=None):
925925
else:
926926
raise TypeError('bad argument passed as gripper')
927927

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)
929931

930932
def _reset_cache(self):
931933
self._path_cache = {}
@@ -1129,7 +1131,8 @@ def fkine(
11291131
T = SE3.Empty()
11301132

11311133
for k, qk in enumerate(q):
1132-
qk = self.toradians(qk)
1134+
if unit == 'deg':
1135+
qk = self.toradians(qk)
11331136
link = end # start with last link
11341137

11351138
# add tool if provided
@@ -2002,9 +2005,9 @@ def jacob0(self, q):
20022005
def jacobe(self, q):
20032006
return self.ets().jacobe(q)
20042007

2005-
def fkine(self, q, unit='rad'):
2008+
def fkine(self, q, unit='rad', end=None, start=None):
20062009

2007-
return self.ets().eval(q, unit=unit)
2010+
return self.ets(start, end).eval(q, unit=unit)
20082011
# --------------------------------------------------------------------- #
20092012

20102013
def plot(
@@ -2189,6 +2192,7 @@ def teach(
21892192
return env
21902193

21912194

2195+
21922196
if __name__ == "__main__": # pragma nocover
21932197

21942198
# import roboticstoolbox as rtb

0 commit comments

Comments
 (0)