@@ -172,13 +172,7 @@ def dynpar(self, name, value, default):
172
172
elif not isinstance (ets , (ETS , ETS2 )):
173
173
raise TypeError ("The ets argument must be of type ETS or ET" )
174
174
175
- if ets .n > 1 :
176
- raise ValueError ("An elementary link can only have one joint variable" )
177
-
178
- if ets .n == 1 and not ets [- 1 ].isjoint :
179
- raise ValueError ("Variable link must be at the end of the ETS" )
180
-
181
- self ._ets = ets
175
+ self .ets = ets
182
176
183
177
# Check parent argument
184
178
if parent is not None :
@@ -198,11 +192,8 @@ def dynpar(self, name, value, default):
198
192
self ._children = []
199
193
200
194
# Set the qlim if provided
201
- if qlim is not None and self .isjoint :
202
- self ._ets [- 1 ].qlim = qlim
203
-
204
- # Initialise the static transform of the Link
205
- self ._init_Ts ()
195
+ if qlim is not None and self .v :
196
+ self .v .qlim = qlim
206
197
207
198
# -------------------------------------------------------------------------- #
208
199
@@ -245,6 +236,46 @@ def Ts(self) -> ndarray:
245
236
"""
246
237
return self ._Ts
247
238
239
+ @overload
240
+ def ets (self : "Link" ) -> ETS :
241
+ ...
242
+
243
+ @overload
244
+ def ets (self : "Link2" ) -> ETS2 :
245
+ ...
246
+
247
+ @property
248
+ def ets (self ):
249
+ return self ._ets
250
+
251
+ @ets .setter
252
+ @overload
253
+ def ets (self : "Link" , new_ets : ETS ):
254
+ ...
255
+
256
+ @ets .setter
257
+ @overload
258
+ def ets (self : "Link2" , new_ets : ETS2 ):
259
+ ...
260
+
261
+ @ets .setter
262
+ def ets (self , new_ets ):
263
+ if new_ets .n > 1 :
264
+ raise ValueError ("An elementary link can only have one joint variable" )
265
+
266
+ if new_ets .n == 1 and not new_ets [- 1 ].isjoint :
267
+ raise ValueError ("Variable link must be at the end of the ETS" )
268
+
269
+ self ._ets = new_ets
270
+ self ._init_Ts ()
271
+
272
+ if self ._ets .n :
273
+ self ._v = self ._ets [- 1 ]
274
+ self ._isjoint = True
275
+ else :
276
+ self ._v = None
277
+ self ._isjoint = False
278
+
248
279
def __repr__ (self ):
249
280
name = self .__class__ .__name__
250
281
if self .name is None :
@@ -325,18 +356,15 @@ def v(self):
325
356
Variable part of link ETS
326
357
:return: joint variable transform
327
358
:rtype: ET instance
328
- The ETS for each ELink comprises a constant part (possible the
359
+ The ETS for each Link comprises a constant part (possible the
329
360
identity) followed by an optional joint variable transform.
330
361
This property returns the latter.
331
362
.. runblock:: pycon
332
363
>>> from roboticstoolbox import ELink, ETS
333
364
>>> link = ELink( ET.tz(0.333) * ET.Rx(90, 'deg') * ETS.Rz() )
334
365
>>> print(link.v)
335
366
"""
336
- if self .isjoint :
337
- return self ._ets [- 1 ]
338
- else :
339
- return None
367
+ return self ._v
340
368
341
369
# -------------------------------------------------------------------------- #
342
370
@@ -396,15 +424,15 @@ def qlim(self) -> Union[ndarray, None]:
396
424
397
425
:seealso: :func:`~islimit`
398
426
"""
399
- if self .isjoint :
400
- return self .ets [ - 1 ] .qlim
427
+ if self .v :
428
+ return self .v .qlim
401
429
else :
402
430
return None
403
431
404
432
@qlim .setter
405
433
def qlim (self , qlim_new : ArrayLike ):
406
- if self .isjoint :
407
- self .ets [ - 1 ] .qlim = qlim_new
434
+ if self .v :
435
+ self .v .qlim = qlim_new
408
436
else :
409
437
raise ValueError ("Can not set qlim on a static joint" )
410
438
@@ -459,7 +487,7 @@ def isflip(self) -> bool:
459
487
- prismatic motion is a negative translation along the z-axis
460
488
461
489
"""
462
- return self .isjoint and self .ets [ - 1 ]. isflip
490
+ return self .v . isflip if self .v else False
463
491
464
492
# -------------------------------------------------------------------------- #
465
493
@@ -768,7 +796,8 @@ def isjoint(self) -> bool:
768
796
>>> robot[1].isjoint # link with joint
769
797
>>> robot[8].isjoint # static link
770
F438
798
"""
771
- return len (self ._ets ) > 0 and self ._ets [- 1 ].isjoint
799
+ # return self.v.isjoint if self.v else False
800
+ return self ._isjoint
772
801
773
802
@property
774
803
def jindex (self ) -> Union [None , int ]:
@@ -786,11 +815,12 @@ def jindex(self) -> Union[None, int]:
786
815
.. note:: ``jindex`` values must be a sequence of integers starting
787
816
at zero.
788
817
"""
789
- return None if not self .isjoint else self ._ets [ - 1 ] ._jindex
818
+ return None if not self .v else self .v ._jindex
790
819
791
820
@jindex .setter
792
821
def jindex (self , j : int ):
793
- self ._ets [- 1 ].jindex = j
822
+ if self .v :
823
+ self .v .jindex = j
794
824
795
825
@property
796
826
def isprismatic (self ) -> bool :
@@ -799,7 +829,8 @@ def isprismatic(self) -> bool:
799
829
:return: True if is prismatic
800
830
:rtype: bool
801
831
"""
802
- return self .isjoint and self ._ets [- 1 ].istranslation
832
+ print (self .v )
833
+ return self .v .istranslation if self .v else False
803
834
804
835
@property
805
836
def isrevolute (self ) -> bool :
@@ -808,11 +839,7 @@ def isrevolute(self) -> bool:
808
839
:return: True if is revolute
809
840
:rtype: bool
810
841
"""
811
- return self .isjoint and self ._ets [- 1 ].isrotation
812
-
813
- @property
814
- def ets (self ):
815
- return self ._ets
842
+ return self .v .isrotation if self .v else False
816
843
817
844
@ov
10000
erload
818
845
def parent (self : "Link" ) -> Union ["Link" , None ]:
@@ -1250,21 +1277,38 @@ def __init__(
1250
1277
# to this specific array. If replaced --> segfault
1251
1278
self ._fk = eye (4 )
1252
1279
1253
- @property
1254
- def ets (self : "Link" ) -> "ETS" :
1255
- """
1256
- Link transform in ETS form
1280
+ # @property
1281
+ # def ets(self: "Link") -> "ETS":
1282
+ # """
1283
+ # Link transform in ETS form
1257
1284
1258
- :return: elementary transform sequence for link transform
1259
- :rtype: ETS or ETS2 instance
1285
+ # :return: elementary transform sequence for link transform
1286
+ # :rtype: ETS or ETS2 instance
1260
1287
1261
- The sequence:
1262
- - has at least one element
1263
- - may include zero or more constant transforms
1264
- - no more than one variable transform, which if present will
1265
- be last in the sequence
1266
- """
1267
- return self ._ets # type: ignore
1288
+ # The sequence:
1289
+ # - has at least one element
1290
+ # - may include zero or more constant transforms
1291
+ # - no more than one variable transform, which if present will
1292
+ # be last in the sequence
1293
+ # """
1294
+ # return self._ets # type: ignore
1295
+
1296
+ # @ets.setter
1297
+ # def ets(self, new_ets: ETS):
1298
+ # if new_ets.n > 1:
1299
+ # raise ValueError("An elementary link can only have one joint variable")
1300
+
1301
+ # if new_ets.n == 1 and not new_ets[-1].isjoint:
1302
+ # raise ValueError("Variable link must be at the end of the ETS")
1303
+
1304
+ # self._ets = new_ets
1305
+
1306
+ # if self._ets.n:
1307
+ # self._v = self._ets[-1]
1308
+ # self._isjoint = True
1309
+ # else:
1310
+ # self._v = None
1311
+ # self._isjoint = False
1268
1312
1269
1313
def A (self , q : float = 0.0 ) -> SE3 :
1270
1314
"""
@@ -1299,21 +1343,38 @@ def __init__(self, ets: ETS2 = ETS2(), jindex: int = None, **kwargs):
1299
1343
if jindex is not None :
1300
1344
self ._ets [- 1 ].jindex = jindex
1301
1345
1302
- @property
1303
- def ets (self ) -> "ETS2" :
1304
- """
1305
- Link transform in ETS form
1306
-
1307
- :return: elementary transform sequence for link transform
1308
- :rtype: ETS or ETS2 instance
1309
-
1310
- The sequence:
1311
- - has at least one element
1312
- - may include zero or more constant transforms
1313
- - no more than one variable transform, which if present will
1314
- be last in the sequence
1315
- """
1316
- return self ._ets # type: ignore
1346
+ # @property
1347
+ # def ets(self) -> "ETS2":
1348
+ # """
1349
+ # Link transform in ETS form
1350
+
1351
+ # :return: elementary transform sequence for link transform
1352
+ # :rtype: ETS or ETS2 instance
1353
+
1354
+ # The sequence:
1355
+ # - has at least one element
1356
+ # - may include zero or more constant transforms
1357
+ # - no more than one variable transform, which if present will
1358
+ # be last in the sequence
1359
+ # """
1360
+ # return self._ets
1361
+
1362
+ # @ets.setter
1363
+ # def ets(self, new_ets: ETS2):
1364
+ # if new_ets.n > 1:
1365
+ # raise ValueError("An elementary link can only have one joint variable")
1366
+
1367
+ # if new_ets.n == 1 and not new_ets[-1].isjoint:
1368
+ # raise ValueError("Variable link must be at the end of the ETS")
1369
+
1370
+ # self._ets = new_ets
1371
+
1372
+ # if self._ets.n:
1373
+ # self._v = self._ets[-1]
1374
+ # self._isjoint = True
1375
+ # else:
1376
+ # self._v = None
1377
+ # self._isjoint = False
1317
1378
1318
1379
def A (self , q : float = 0.0 ) -> SE2 :
1319
1380
"""
0 commit comments