8000 Formatted Elink · A905275/robotics-toolbox-python@ee5442c · GitHub
[go: up one dir, main page]

Skip to content 8000

Commit ee5442c

Browse files
committed
Formatted Elink
1 parent ace04f0 commit ee5442c

File tree

1 file changed

+76
-59
lines changed

1 file changed

+76
-59
lines changed

roboticstoolbox/robot/ELink.py

Lines changed: 76 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212

1313

1414
class BaseELink(Link):
15-
1615
def __init__(self, name=None, parent=None, joint_name=None, **kwargs):
1716

1817
super().__init__(**kwargs)
@@ -23,7 +22,7 @@ def __init__(self, name=None, parent=None, joint_name=None, **kwargs):
2322
if isinstance(parent, (str, BaseELink)):
2423
self._parent = parent
2524
else:
26-
raise TypeError('parent must be BaseELink subclass or str')
25+
raise TypeError("parent must be BaseELink subclass or str")
2726
else:
2827
self._parent = None
2928

@@ -292,11 +291,11 @@ def collision(self, coll):
292291
if isinstance(gi, Shape):
293292
new_coll.append(gi)
294293
else:
295-
raise TypeError('Collision must be of Shape class')
294+
raise TypeError("Collision must be of Shape class")
296295
elif isinstance(coll, Shape):
297296
new_coll.append(coll)
298297
else:
299-
raise TypeError('Geometry must be of Shape class or list of Shape')
298+
raise TypeError("Geometry must be of Shape class or list of Shape")
300299

301300
self._collision = new_coll
302301

@@ -309,11 +308,11 @@ def geometry(self, geom):
309308
if isinstance(gi, Shape):
310309
new_geom.append(gi)
311310
else:
312-
raise TypeError('Geometry must be of Shape class')
311+
raise TypeError("Geometry must be of Shape class")
313312
elif isinstance(geom, Shape):
314313
new_geom.append(geom)
315314
else:
316-
raise TypeError('Geometry must be of Shape class or list of Shape')
315+
raise TypeError("Geometry must be of Shape class or list of Shape")
317316

318317
self._geometry = new_geom
319318

@@ -355,20 +354,14 @@ class ELink(BaseELink):
355354
:seealso: :class:`Link`, :class:`DHLink`
356355
"""
357356

358-
def __init__(
359-
self,
360-
ets=ETS(),
361-
v=None,
362-
jindex=None,
363-
**kwargs):
357+
def __init__(self, ets=ETS(), v=None, jindex=None, **kwargs):
364358

365359
# process common options
366360
super().__init__(**kwargs)
367361

368362
# check we have an ETS
369363
if not isinstance(ets, ETS):
370-
raise TypeError(
371-
'The ets argument must be of type ETS')
364+
raise TypeError("The ets argument must be of type ETS")
372365

373366
self._ets = ets
374367

@@ -388,12 +381,11 @@ def __init__(
388381
if v is None:
389382
self._joint = False
390383
elif not isinstance(v, ETS):
391-
raise TypeError('v must be of type ETS')
384+
raise TypeError("v must be of type ETS")
392385
elif not v[0].isjoint:
393-
raise ValueError('v must be a variable ETS')
386+
raise ValueError("v must be a variable ETS")
394387
elif len(v) > 1:
395-
raise ValueError(
396-
"An elementary link can only have one joint variable")
388+
raise ValueError("An elementary link can only have one joint variable")
397389
else:
398390
self._joint = True
399391

@@ -418,17 +410,17 @@ def _get_fknm(self):
418410
if jindex is None:
419411
jindex = 0
420412

421-
if self._v.axis == 'Rx':
413+
if self._v.axis == "Rx":
422414
axis = 0
423-
elif self._v.axis == 'Ry':
415+
elif self._v.axis == "Ry":
424416
axis = 1
425-
elif self._v.axis == 'Rz':
417+
elif self._v.axis == "Rz":
426418
axis = 2
427-
elif self._v.axis == 'tx':
419+
elif self._v.axis == "tx":
428420
axis = 3
429-
elif self._v.axis == 'ty':
421+
elif self._v.axis == "ty":
430422
axis = 4
431-
elif self._v.axis == 'tz':
423+
elif self._v.axis == "tz":
432424
axis = 5
433425

434426
if self.parent is None:
@@ -453,22 +445,38 @@ def _get_fknm(self):
453445
shape_sT.append(shap._sT)
454446
shape_sq.append(shap._sq)
455447

456-
return isflip, axis, jindex, parent, shape_base, shape_wT, \
457-
shape_sT, shape_sq
448+
return isflip, axis, jindex, parent, shape_base, shape_wT, shape_sT, shape_sq
458449

459450
def _init_fknm(self):
460451
if isinstance(self.parent, str):
461452
# Initialise later
462453
return
463454

464-
isflip, axis, jindex, parent, \
465-
shape_base, shape_wT, shape_sT, shape_sq = self._get_fknm()
455+
(
456+
isflip,
457+
axis,
458+
jindex,
459+
parent,
460+
shape_base,
461+
shape_wT,
462+
shape_sT,
463+
shape_sq,
464+
) = self._get_fknm()
466465

467466
self._fknm = fknm.link_init(
468-
self.isjoint, isflip, axis, jindex, len(shape_base),
469-
self._Ts, self._fk,
470-
shape_base, shape_wT, shape_sT, shape_sq,
471-
parent)
467+
self.isjoint,
468+
isflip,
469+
axis,
470+
jindex,
471+
len(shape_base),
472+
self._Ts,
473+
self._fk,
474+
shape_base,
475+
shape_wT,
476+
shape_sT,
477+
shape_sq,
478+
parent,
479+
)
472480

473481
def _update_fknm(self):
474482

@@ -480,15 +488,32 @@ def _update_fknm(self):
480488
except AttributeError:
481489
return
482490

483-
isflip, axis, jindex, parent, \
484-
shape_base, shape_wT, shape_sT, shape_sq = self._get_fknm()
491+
(
492+
isflip,
493+
axis,
494+
jindex,
495+
parent,
496+ shape_base,
497+
shape_wT,
498+
shape_sT,
499+
shape_sq,
500+
) = self._get_fknm()
485501

486502
fknm.link_update(
487503
self._fknm,
488-
self.isjoint, isflip, axis, jindex, len(shape_base),
489-
self._Ts, self._fk,
490-
shape_base, shape_wT, shape_sT, shape_sq,
491-
parent)
504+
self.isjoint,
505+
isflip,
506+
axis,
507+
jindex,
508+
len(shape_base),
509+
self._Ts,
510+
self._fk,
511+
shape_base,
512+
shape_wT,
513+
shape_sT,
514+
shape_sq,
515+
parent,
516+
)
492517

493518
def _init_Ts(self):
494519
# Number of transforms in the ETS excluding the joint variable
@@ -508,7 +533,7 @@ def _init_Ts(self):
508533
for et in self._ets:
509534
# constant transforms only
510535
if et.isjoint:
511-
raise ValueError('The transforms in ets must be constant')
536+
raise ValueError("The transforms in ets must be constant")
512537

513538
# if first:
514539
# T = et.T()
@@ -522,7 +547,7 @@ def _init_Ts(self):
522547

523548
elif isinstance(self._ets, SE3):
524549
self._Ts = self._ets
525-
raise RuntimeError('this shouldnt happen')
550+
raise RuntimeError("this shouldnt happen")
526551

527552
@property
528553
def geometry(self):
@@ -562,11 +587,11 @@ def collision(self, coll):
562587
if isinstance(gi, Shape):
563588
new_coll.append(gi)
564589
else:
565-
raise TypeError('Collision must be of Shape class')
590+
raise TypeError("Collision must be of Shape class")
566591
elif isinstance(coll, Shape):
567592
new_coll.append(coll)
568593
else:
569-
raise TypeError('Geometry must be of Shape class or list of Shape')
594+
raise TypeError("Geometry must be of Shape class or list of Shape")
570595

571596
self._collision = new_coll
572597
self._update_fknm()
@@ -581,11 +606,11 @@ def geometry(self, geom):
581606
if isinstance(gi, Shape):
582607
new_geom.append(gi)
583608
else:
584-
raise TypeError('Geometry must be of Shape class')
609+
raise TypeError("Geometry must be of Shape class")
585610
elif isinstance(geom, Shape):
586611
new_geom.append(geom)
587612
else:
588-
raise TypeError('Geometry must be of Shape class or list of Shape')
613+
raise TypeError("Geometry must be of Shape class or list of Shape")
589614

590615
self._geometry = new_geom
591616
self._update_fknm()
@@ -652,21 +677,14 @@ def A(self, q=0.0, fast=False):
652677

653678

654679
class ELink2(BaseELink):
655-
656-
def __init__(
657-
self,
658-
ets=ETS2(),
659-
v=None,
660-
jindex=None,
661-
**kwargs):
680+
def __init__(self, ets=ETS2(), v=None, jindex=None, **kwargs):
662681

663682
# process common options
664683
super().__init__(**kwargs)
665684

666685
# check we have an ETS
667686
if not isinstance(ets, ETS2):
668-
raise TypeError(
669-
'The ets argument must be of type ETS2')
687+
raise TypeError("The ets argument must be of type ETS2")
670688

671689
self._ets = ets
672690

@@ -685,12 +703,11 @@ def __init__(
685703
if v is None:
686704
self._joint = False
687705
elif not isinstance(v, ETS2):
688-
raise TypeError('v must be of type ETS2')
706+
raise TypeError("v must be of type ETS2")
689707
elif not v[0].isjoint:
690-
raise ValueError('v must be a variable ETS')
708+
raise ValueError("v must be a variable ETS")
691709
elif len(v) > 1:
692-
raise ValueError(
693-
"An elementary link can only have one joint variable")
710+
raise ValueError("An elementary link can only have one joint variable")
694711
else:
695712
self._joint = True
696713

@@ -711,15 +728,15 @@ def _init_Ts(self):
711728
for et in self._ets:
712729
# constant transforms only
713730
if et.isjoint:
714-
raise ValueError('The transforms in ets must be constant')
731+
raise ValueError("The transforms in ets must be constant")
715732

716733
T = T @ et.T()
717734

718735
self._Ts = T
719736

720737
elif isinstance(self._ets, SE3):
721738
self._Ts = self._ets
722-
raise RuntimeError('this shouldnt happen')
739+
raise RuntimeError("this shouldnt happen")
723740

724741
def A(self, q=0.0, **kwargs):
725742
"""

0 commit comments

Comments
 (0)
0