10000 Rework and polish · ctc-eng/robotics-toolbox-python@45fda8c · GitHub
[go: up one dir, main page]

Skip to content

Commit 45fda8c

Browse files
committed
Rework and polish
remove jtype, STATIC, VARIABLE and replace with .isjoint predicate add isrevolute and isprismatic predictes lots of doco and examples passes
1 parent 368b889 commit 45fda8c

File tree

4 files changed

+584
-242
lines changed

4 files changed

+584
-242
lines changed

roboticstoolbox/robot/ELink.py

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -55,9 +55,6 @@ def __init__(
5555

5656
super(ELink, self).__init__(**kwargs)
5757

58-
self.STATIC = 0
59-
self.VARIABLE = 1
60-
6158
if isinstance(ets, ETS):
6259
self._ets = ets
6360
else:
@@ -81,7 +78,7 @@ def __init__(
8178
if isinstance(ets, ETS):
8279
self._Ts = SE3()
8380
for i in range(self.M):
84-
if ets[i].jtype is not ets[i].STATIC:
81+
if ets[i].isjoint:
8582
raise ValueError('The transforms in ets must be constant')
8683

8784
if not isinstance(ets[i].T(), SE3):
@@ -94,16 +91,16 @@ def __init__(
9491

9592
# Check the variable joint
9693
if v is None:
97-
self._jtype = self.STATIC
94+
self._joint = False
9895
elif not isinstance(v, ETS):
9996
raise TypeError('v must be of type ETS')
100-
elif v[0].jtype is v[0].STATIC:
97+
elif not v[0].isjoint:
10198
raise ValueError('v must be a variable ETS')
10299
elif len(v) > 1:
103100
raise ValueError(
104101
"An elementary link can only have one joint variable")
105102
else:
106-
self._jtype = self.VARIABLE
103+
self._joint = True
107104

108105
self._v = v
109106

@@ -130,15 +127,13 @@ def geometry(self):
130127
return self._geometry
131128

132129
@property
133-
def jtype(self):
134-
return self._jtype
130+
def isjoint(self):
131+
return self._joint
135132

136133
@property
137134
def ets(self):
138135
return self._ets
139136

140-
141-
142137
# @property
143138
# def parent_name(self):
144139
# return self._parent_name
@@ -233,7 +228,7 @@ def A(self, 10000 q=None, fast=False):
233228
# j = 0
234229
# tr = SE3()
235230

236-
if self.jtype == self.VARIABLE and q is None:
231+
if self.isjoint and q is None:
237232
raise ValueError("q is required for variable joints")
238233

239234
# for k in range(self.M):

roboticstoolbox/robot/ERobot.py

Lines changed: 12 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ def __init__(
101101

102102
def add_links(link, lst, q_idx):
103103

104-
if link.jtype == link.VARIABLE:
104+
if link.isjoint:
105105
q_idx.append(len(lst))
106106

107107
lst.append(link)
@@ -345,7 +345,7 @@ def qlim(self):
345345
j = 0
346346

347347
for i in range(self.M):
348-
if self.ets[i].jtype == self.ets[i].VARIABLE:
348+
if self.ets[i].isjoint:
349349
v[:, j] = self.ets[i].qlim
350350
j += 1
351351

@@ -456,7 +456,7 @@ def fkine(self, q=None):
456456
tr = self.base
457457

458458
for link in self._fkpath:
459-
if link.jtype == link.VARIABLE:
459+
if link.isjoint:
460460
T = link.A(q[j, i])
461461
j += 1
462462
else:
@@ -489,7 +489,7 @@ def fkine_graph(self, q=None, from_link=None, to_link=None):
489489
tr = self.base.A
490490

491491
for link in path:
492-
if link.jtype == link.VARIABLE:
492+
if link.isjoint:
493493
T = link.A(q[j], fast=True)
494494
j += 1
495495
else:
@@ -533,7 +533,7 @@ def fkine_all(self, q=None):
533533
# Tall = SE3()
534534
j = 0
535535

536-
if self.ets[0].jtype == self.ets[0].VARIABLE:
536+
if self.ets[0].isjoint:
537537
self.ets[0]._fk = self.base * self.ets[0].A(q[j])
538538
j += 1
539539
else:
@@ -546,7 +546,7 @@ def fkine_all(self, q=None):
546546
gi.wT = self.ets[0]._fk
547547

548548
for i in range(1, self.M):
549-
if self.ets[i].jtype == self.ets[i].VARIABLE:
549+
if self.ets[i].isjoint:
550550
t = self.ets[i].A(q[j])
551551
j += 1
552552
else:
@@ -643,13 +643,13 @@ def get_path(self, from_link, to_link):
643643
link = to_link
644644

645645
path.append(link)
646-
if link.jtype is link.VARIABLE:
646+
if link.isjoint:
647647
n += 1
648648

649649
while link != from_link:
650650
link = link.parent
651651
path.append(link)
652-
if link.jtype is link.VARIABLE:
652+
if link.isjoint:
653653
n += 1
654654

655655
path.reverse()
@@ -691,9 +691,7 @@ def jacob0(
691691

692692
for link in path:
693693

694-
if link.jtype is link.STATIC:
695-
U = U @ link.A(fast=True)
696-
else:
694+
if link.isjoint:
697695
U = U @ link.A(q[j], fast=True)
698696

699697
if link == to_link:
@@ -732,6 +730,9 @@ def jacob0(
732730
J[3:, j] = np.array([0, 0, 0])
733731

734732
j += 1
733+
else:
734+
U = U @ link.A(fast=True)
735+
735736

736737
return J
737738

0 commit comments

Comments
 (0)
0