@@ -315,7 +315,7 @@ def jindex(self, j):
315
315
self .data [0 ].jindex = j
316
316
317
317
@property
318
- def isrevolute (self ):
318
+ def isrotation (self ):
319
319
"""
320
320
Test if ET is a rotation
321
321
@@ -328,14 +328,14 @@ def isrevolute(self):
328
328
329
329
>>> from roboticstoolbox import ETS
330
330
>>> e = ETS.tx(1)
331
- >>> e.isrevolute
331
+ >>> e.isrotation
332
332
>>> e = ETS.rx()
333
- >>> e.isrevolute
333
+ >>> e.isrotation
334
334
"""
335
335
return self .axis [0 ] == 'R'
336
336
337
337
@property
338
- def isprismatic (self ):
338
+ def istranslation (self ):
339
339
"""
340
340
Test if ET is a translation
341
341
@@ -348,9 +348,9 @@ def isprismatic(self):
348
348
349
349
>>> from roboticstoolbox import ETS
350
350
>>> e = ETS.tx(1)
351
- >>> e.isprismatic
351
+ >>> e.istranslation
352
352
>>> e = ETS.rx()
353
- >>> e.isprismatic
353
+ >>> e.istranslation
354
354
"""
355
355
return self .axis [0 ] == 't'
356
356
@@ -394,7 +394,7 @@ def structure(self):
394
394
395
395
"""
396
396
return '' .join (
397
- ['R' if self .isrevolute else 'P' for i in self .joints ()])
397
+ ['R' if self .isrotation else 'P' for i in self .joints ()])
398
398
399
399
@property
400
400
def qlim (self ):
@@ -505,7 +505,7 @@ def eval(self, q=None, unit='rad'):
505
505
qj = q .pop (0 )
506
506
else :
507
507
qj = q [et .jindex ]
508
- if et .isrevolute and unit == 'deg' :
508
+ if et .isrotation and unit == 'deg' :
509
509
qj *= np .pi / 180.0
510
510
511
511
Tk = et .T (qj )
@@ -680,13 +680,13 @@ def __str__(self, q=None):
680
680
s = f"{ et .axis } ({ qvar } )"
681
681
j += 1
682
682
683
- elif et .isrevolute :
683
+ elif et .isrotation :
684
684
if issymbol (et .eta ):
685
685
s = f"{ et .axis } ({ et .eta :.4g} )"
686
686
else :
687
687
s = f"{ et .axis } ({ et .eta * 180 / np .pi :.4g} °)"
688
688
689
- elif et .isprismatic :
689
+ elif et .istranslation :
690
690
s = f"{ et .axis } ({ et .eta :.4g} )"
691
691
692
692
elif et .isconstant :
@@ -944,7 +944,7 @@ def teach(self, *args, **kwargs):
944
944
945
945
if isinstance (self , ETS ):
946
946
robot = ERobot (self )
947
- else :
947
+ elif isinstance ( self , ETS2 ) :
948
948
robot = ERobot2 (self )
949
949
950
950
robot .teach (* args , ** kwargs )
@@ -1047,7 +1047,7 @@ def rx(cls, eta=None, unit='rad', **kwargs):
1047
1047
angle, i.e. a revolute robot joint. ``j`` or ``flip`` can be set in
1048
1048
this case.
1049
1049
1050
- :seealso: :func:`ETS`, :func:`isrevolute `
1050
+ :seealso: :func:`ETS`, :func:`isrotation `
1051
1051
:SymPy: supported
1052
1052
"""
1053
1053
return cls (axis = 'Rx' , eta = eta , axis_func = trotx , unit = unit , ** kwargs )
@@ -1074,7 +1074,7 @@ def ry(cls, eta=None, unit='rad', **kwargs):
1074
1074
angle, i.e. a revolute robot joint. ``j`` or ``flip`` can be set in
1075
1075
this case.
1076
1076
1077
- :seealso: :func:`ETS`, :func:`isrevolute `
1077
+ :seealso: :func:`ETS`, :func:`isrotation `
1078
1078
:SymPy: supported
1079
1079
"""
1080
1080
return cls (axis = 'Ry' , eta = eta , axis_func = troty , unit = unit , ** kwargs )
@@ -1101,7 +1101,7 @@ def rz(cls, eta=None, unit='rad', **kwargs):
1101
1101
angle, i.e. a revolute robot joint. ``j`` or ``flip`` can be set in
1102
1102
this case.
1103
1103
1104
- :seealso: :func:`ETS`, :func:`isrevolute `
1104
+ :seealso: :func:`ETS`, :func:`isrotation `
1105
1105
:SymPy: supported
1106
1106
"""
1107
1107
return cls (axis = 'Rz' , eta = eta , axis_func = trotz , unit = unit , ** kwargs )
@@ -1126,7 +1126,7 @@ def tx(cls, eta=None, **kwargs):
1126
1126
variable distance, i.e. a prismatic robot joint. ``j`` or ``flip``
1127
1127
can be set in this case.
1128
1128
1129
- :seealso: :func:`ETS`, :func:`isprismatic `
1129
+ :seealso: :func:`ETS`, :func:`istranslation `
1130
1130
:SymPy: supported
1131
1131
"""
1132
1132
@@ -1161,7 +1161,7 @@ def ty(cls, eta=None, **kwargs):
1161
1161
variable distance, i.e. a prismatic robot joint. ``j`` or ``flip``
1162
1162
can be set in this case.
1163
1163
1164
- :seealso: :func:`ETS`, :func:`isprismatic `
1164
+ :seealso: :func:`ETS`, :func:`istranslation `
1165
1165
:SymPy: supported
1166
1166
"""
1167
1167
def axis_func (eta ):
@@ -1196,7 +1196,7 @@ def tz(cls, eta=None, **kwargs):
1196
1196
variable distance, i.e. a prismatic robot joint. ``j`` or ``flip``
1197
1197
can be set in this case.
1198
1198
1199
- :seealso: :func:`ETS`, :func:`isprismatic `
1199
+ :seealso: :func:`ETS`, :func:`istranslation `
1200
1200
:SymPy: supported
1201
1201
"""
1202
1202
def axis_func (eta ):
@@ -1511,7 +1511,7 @@ def r(cls, eta=None, unit='rad', **kwargs):
1511
1511
.. note:: In the 2D case this is rotation around the normal to the
1512
1512
xy-plane.
1513
1513
1514
- :seealso: :func:`ETS`, :func:`isrevolute `
1514
+ :seealso: :func:`ETS`, :func:`isrotation `
1515
1515
"""
1516
1516
return cls (
1517
1517
axis = 'R' , eta = eta ,
@@ -1537,7 +1537,7 @@ def tx(cls, eta=None, **kwargs):
1537
1537
variable distance, i.e. a prismatic robot joint. ``j`` or ``flip``
1538
1538
can be set in this case.
1539
1539
1540
- :seealso: :func:`ETS`, :func:`isprismatic `
1540
+ :seealso: :func:`ETS`, :func:`istranslation `
1541
1541
"""
1542
1542
return cls (
1543
1543
axis = 'tx' , eta = eta ,
0 commit comments