@@ -946,33 +946,22 @@ class ERobot(BaseERobot):
946
946
947
947
def __init__ (self , arg , ** kwargs ):
948
948
949
-
950
949
if isinstance (arg , DHRobot ):
951
950
# we're passed a DHRobot object
952
951
# TODO handle dynamic parameters if given
953
952
arg = arg .ets ()
954
953
955
- link_number = 0
956
954
if isinstance (arg , ETS ):
957
955
# we're passed an ETS string
958
956
ets = arg
959
957
links = []
960
-
961
958
# chop it up into segments, a link frame after every joint
962
- start = 0
963
- for j , k in enumerate (ets .joints ()):
964
- ets_j = ets [start :k + 1 ]
965
- start = k + 1
966
- if j == 0 :
967
- parent = None
968
- else :
969
- parent = links [- 1 ]
959
+ parent = None
960
+ for j , ets_j in enumerate (arg .split ()):
970
961
elink = ELink (ets_j , parent = parent , name = f"link{ j :d} " )
962
+ parent = elink
971
963
links .append (elink )
972
- tail = arg [start :]
973
- if len (tail ) > 0 :
974
- elink = ELink (tail , parent = links [- 1 ], name = f"link{ j + 1 :d} " )
975
- links .append (elink )
964
+
976
965
elif islistof (arg , ELink ):
977
966
links = arg
978
967
else :
@@ -2114,22 +2103,13 @@ def __init__(self, arg, **kwargs):
2114
2103
# we're passed an ETS string
2115
2104
ets = arg
2116
2105
links = []
2117
-
2118
2106
# chop it up into segments, a link frame after every joint
2119
- start = 0
2120
- for j , k in enumerate (ets .joints ()):
2121
- ets_j = ets [start :k + 1 ]
2122
- start = k + 1
2123
- if j == 0 :
2124
- parent = None
2125
- else :
2126
- parent = links [- 1 ]
2107
+ parent = None
2108
+ for j , ets_j in enumerate (arg .split ()):
2127
2109
elink = ELink2 (ets_j , parent = parent , name = f"link{ j :d} " )
2110
+ parent = elink
2128
2111
links .append (elink )
2129
- tail = arg [start :]
2130
- if len (tail ) > 0 :
2131
- elink = ELink2 (tail , parent = links [- 1 ], name = f"link{ j + 1 :d} " )
2132
- links .append (elink )
2112
+
2133
2113
elif islistof (arg , ELink2 ):
2134
2114
links = arg
2135
2115
else :
0 commit comments