@@ -123,9 +123,9 @@ def _init_Ts(self):
123123
124124 def __repr__ (self ):
125125 name = self .__class__ .__name__
126- s = " ets=" + str ( self .ets ())
126+ s = f" { self . name } , ets={ self .ets ()} "
127127 if self .parent is not None :
128- s += ", parent=" + str ( self .parent .name )
128+ s += f ", parent={ self .parent .name } "
129129 args = [s ] + super ()._params ()
130130 return name + "(" + ", " .join (args ) + ")"
131131
@@ -145,32 +145,113 @@ def __str__(self):
145145
146146 @property
147147 def v (self ):
148+ """
149+ Variable part of link ETS
150+
151+ :return: joint variable transform
152+ :rtype: ETS instance
153+
154+ The ETS for each ELink comprises a constant part (possible the identity)
155+ followed by an optional joint variable transform. This property returns
156+ the latter.
157+
158+ .. runblock:: pycon
159+
160+ >>> from roboticstoolbox import ELink, ETS
161+ >>> link = ELink( ETS.tz(0.333) * ETS.rx(90, 'deg') * ETS.rz() )
162+ >>> print(link.v)
163+ """
148164 return self ._v
149165
150166 @property
151167 def Ts (self ):
152- return self ._Ts
168+ """
169+ Constant part of link ETS
153170
154- @property
155- def collision (self ):
156- return self ._collision
171+ :return: constant part of link transform
172+ :rtype: SE3 instance
173+
174+ The ETS for each ELink comprises a constant part (possible the identity)
175+ followed by an optional joint variable transform. This property returns
176+ the constant part. If no constant part is given, this returns an
177+ identity matrix.
178+
179+ .. runblock:: pycon
180+
181+ >>> from roboticstoolbox import ELink, ETS
182+ >>> link = ELink( ETS.tz(0.333) * ETS.rx(90, 'deg') * ETS.rz() )
183+ >>> link.Ts
184+ >>> link = ELink( ETS.rz() )
185+ >>> link.Ts
186+ """
187+ return self ._Ts
157188
158- @property
159- def geometry (self ):
160- return self ._geometry
161189
162190 @property
163191 def isjoint (self ):
192+ """
193+ Test if link has joint
194+
195+ :return: test if link has a joint
196+ :rtype: bool
197+
198+ The ETS for each ELink comprises a constant part (possible the identity)
199+ followed by an optional joint variable transform. This property returns the
200+ whether the
201+
202+ .. runblock:: pycon
203+
204+ >>> from roboticstoolbox import models
205+ >>> robot = models.URDF.Panda()
206+ >>> robot[1].isjoint # link with joint
207+ >>> robot[8].isjoint # static link
208+ """
164209 return self ._v is not None
165210
166211 @property
167212 def jindex (self ):
213+ """
214+ Get/set joint index
215+
216+ - ``link.jindex`` is the joint index
217+ :return: joint index
218+ :rtype: int
219+ - ``link.jindex = ...`` checks and sets the joint index
220+
221+ For a serial-link manipulator the joints are numbered starting at zero
222+ and increasing sequentially toward the end-effector. For branched
223+ mechanisms this is not so straightforward.
224+
225+ The link's ``jindex`` property specifies the index of its joint
226+ variable within a vector of joint coordinates.
227+
228+ .. note:: ``jindex`` values must be a sequence of integers starting
229+ at zero.
230+ """
168231 return self ._jindex
169232
170233 @jindex .setter
171234 def jindex (self , j ):
172235 self ._jindex = j
173236
237+ def isrevolute (self ):
238+ """
239+ Checks if the joint is of revolute type
240+
241+ :return: Ture if is revolute
242+ :rtype: bool
243+ """
244+ return self .v .isrevolute
245+
246+ def isprismatic (self ):
247+ """
248+ Checks if the joint is of prismatic type
249+
250+ :return: Ture if is prismatic
251+ :rtype: bool
252+ """
253+ return self .v .isprismatic
254+
174255 # @property
175256 # def ets(self):
176257 # return self._ets
@@ -185,6 +266,21 @@ def jindex(self, j):
185266
186267 @property
187268 def parent (self ):
269+ """
270+ Parent link
271+
272+ :return: Link's parent
273+ :rtype: ELink instance
274+
275+ This is a reference to
276+
277+ .. runblock:: pycon
278+
279+ >>> from roboticstoolbox import models
280+ >>> robot = models.URDF.Panda()
281+ >>> robot[0].parent # base link has no parent
282+ >>> robot[1].parent # second link's parent
283+ """
188284 return self ._parent
189285
190286 @property
@@ -195,39 +291,14 @@ def child(self):
195291 def M (self ):
196292 return self ._M
197293
198- @collision .setter
199- def collision (self , coll ):
200- new_coll = []
201-
202- if isinstance (coll , list ):
203- for gi in coll :
204- if isinstance (gi , rp .Shape ):
205- new_coll .append (gi )
206- else :
207- raise TypeError ('Collision must be of Shape class' )
208- elif isinstance (coll , rp .Shape ):
209- new_coll .append (coll )
210- else :
211- raise TypeError ('Geometry must be of Shape class or list of Shape' )
212-
213- self ._collision = new_coll
214-
215- @geometry .setter
216- def geometry (self , geom ):
217- new_geom = []
294+ @property
295+ def collision (self ):
296+ return self ._collision
218297
219- if isinstance (geom , list ):
220- for gi in geom :
221- if isinstance (gi , rp .Shape ):
222- new_geom .append (gi )
223- else :
224- raise TypeError ('Geometry must be of Shape class' )
225- elif isinstance (geom , rp .Shape ):
226- new_geom .append (geom )
227- else :
228- raise TypeError ('Geometry must be of Shape class or list of Shape' )
298+ @property
299+ def geometry (self ):
300+ return self ._geometry
229301
230- self ._geometry = new_geom
231302
232303 # @r.setter
233304 # def r(self, T):
@@ -282,6 +353,40 @@ def ets(self):
282353 else :
283354 return self ._ets * self .v
284355
356+ @collision .setter
357+ def collision (self , coll ):
358+ new_coll = []
359+
360+ if isinstance (coll , list ):
361+ for gi in coll :
362+ if isinstance (gi , rp .Shape ):
363+ new_coll .append (gi )
364+ else :
365+ raise TypeError ('Collision must be of Shape class' )
366+ elif isinstance (coll , rp .Shape ):
367+ new_coll .append (coll )
368+ else :
369+ raise TypeError ('Geometry must be of Shape class or list of Shape' )
370+
371+ self ._collision = new_coll
372+
373+ @geometry .setter
374+ def geometry (self , geom ):
375+ new_geom = []
376+
377+ if isinstance (geom , list ):
378+ for gi in geom :
379+ if isinstance (gi , rp .Shape ):
380+ new_geom .append (gi )
381+ else :
382+ raise TypeError ('Geometry must be of Shape class' )
383+ elif isinstance (geom , rp .Shape ):
384+ new_geom .append (geom )
385+ else :
386+ raise TypeError ('Geometry must be of Shape class or list of Shape' )
387+
388+ self ._geometry = new_geom
389+
285390 def closest_point (self , shape , inf_dist = 1.0 ):
286391 '''
287392 closest_point(shape, inf_dist) returns the minimum euclidean
0 commit comments