Skip to content

Commit 990e4eb

Browse files
committed
Polish repr and str
make it handle symbolics polish doco
1 parent 168756d commit 990e4eb

File tree

5 files changed

+168
-46
lines changed

5 files changed

+168
-46
lines changed

roboticstoolbox/robot/DHLink.py

Lines changed: 18 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -138,19 +138,30 @@ def __add__(self, L):
138138

139139
def __str__(self):
140140

141-
if not self.sigma:
142-
s = "Revolute theta=q{} +{: .2f}, d={: .2f}, a={: .2f}, " \
143-
"alpha={: .2f}".format(
144-
self.id, self.offset, self.d, self.a, self.alpha)
141+
if self.offset == 0:
142+
offset = ""
143+
else:
144+
offset = f" + {self.offset}"
145+
if self.isrevolute():
146+
s = f"Revolute: theta=q{self.id}{offset}, d={self.d}, " \
147+
f"a={self.a}, alpha={self.alpha}"
145148
else:
146-
s = "Prismatic theta={: .2f}, d=q{} +{: .2f}, a={: .2f}, " \
149+
s = "Prismatic: theta={: .2f}, d=q{} +{: .2f}, a={: .2f}, " \
147150
"alpha={: .2f}".format(
148151
self.theta, self.id, self.offset, self.a, self.alpha, )
149-
150152
return s
151153

152154
def __repr__(self):
153-
return str(self)
155+
name = self.__class__.__name__
156+
args = []
157+
if self.isrevolute():
158+
self._format(args, "d")
159+
else:
160+
self._format(args, "theta")
161+
self._format(args, "a")
162+
self._format(args, "alpha")
163+
args.extend(super()._params())
164+
return name + "(" + ", ".join(args) + ")"
154165

155166

156167
@property

roboticstoolbox/robot/DHRobot.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -117,11 +117,14 @@ def qs(j, link):
117117
else:
118118
return f"q{j:d} + {L.offset * deg:}\u00b0"
119119

120-
def angle(theta):
120+
def angle(theta, fmt=None):
121121
if sym.issymbol(theta):
122122
return "<<red>>" + str(theta)
123123
else:
124-
return str(theta * deg) + "\u00b0"
124+
if fmt is not None:
125+
return fmt.format(theta * deg) + "\u00b0"
126+
else:
127+
return str(theta * deg) + "\u00b0"
125128

126129
has_qlim = any([link._qlim is not None for link in self])
127130
if has_qlim:
@@ -209,7 +212,7 @@ def angle(theta):
209212
if L.isprismatic():
210213
qlist.append(f"{q[i]:.3g}")
211214
else:
212-
qlist.append(angle(q[i]))
215+
qlist.append(angle(q[i], "{:.3g}"))
213216
table.row(name, *qlist)
214217

215218
s += "\n" + str(table)

roboticstoolbox/robot/ELink.py

Lines changed: 28 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,7 @@
1313

1414
class ELink(Link):
1515
"""
16-
A link superclass for all link types. A Link object holds all information
17-
related to a robot joint and link such as kinematics parameters,
18-
rigid-body inertial parameters, motor and transmission parameters.
16+
ETS link class
1917
2018
:param ets: kinematic - The elementary transforms which make up the link
2119
:type ets: ETS
@@ -38,19 +36,25 @@ class ELink(Link):
3836
:param G: dynamic - gear ratio
3937
:type G: float
4038
39+
The ELink object holds all information related to a robot link and can form
40+
a serial-connected chain or a rigid-body tree.
41+
42+
It inherits from the Link class which provides common functionality such
43+
as joint and link such as kinematics parameters,
44+
.
45+
4146
:references:
4247
- Kinematic Derivatives using the Elementary Transform Sequence,
4348
J. Haviland and P. Corke
4449
50+
:seealso: :class:`Link`, :class:`DHLink`
4551
"""
4652

4753
def __init__(
4854
self,
4955
ets=ETS(),
5056
v=None,
5157
parent=None,
52-
geometry=[],
53-
collision=[],
5458
**kwargs):
5559

5660
# process common options
@@ -110,11 +114,26 @@ def __init__(
110114

111115
self._v = v
112116

113-
self.geometry = geometry
114-
self.collision = collision
115-
116117
def __repr__(self):
117-
return self.name
118+
name = self.__class__.__name__
119+
s = "ets=" + str(self.ets)
120+
if self.parent is not None:
121+
s += ", parent=" + str(self.parent.name)
122+
args = [s] + super()._params()
123+
return name + "(" + ", ".join(args) + ")"
124+
125+
def __str__(self):
126+
"""
127+
Pretty prints the ETS Model of the link. Will output angles in degrees
128+
129+
:return: Pretty print of the robot link
130+
:rtype: str
131+
"""
132+
if self.parent is None:
133+
parent = ""
134+
else:
135+
parent = f" [{self.parent.name}]"
136+
return f"{self.name}{parent}: {self.ets}"
118137

119138
@property
120139
def v(self):
@@ -204,15 +223,6 @@ def geometry(self, geom):
204223

205224

206225

207-
def __str__(self):
208-
"""
209-
Pretty prints the ETS Model of the link. Will output angles in degrees
210-
211-
:return: Pretty print of the robot link
212-
:rtype: str
213-
"""
214-
return str(self._ets)
215-
216226

217227

218228

roboticstoolbox/robot/ETS.py

Lines changed: 39 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
from collections import UserList, namedtuple
77
import numpy as np
88
from spatialmath import SE3
9-
from spatialmath.base import getvector, getunit, trotx, troty, trotz
9+
from spatialmath.base import getvector, getunit, trotx, troty, trotz, issymbol
1010

1111

1212
class ETS(UserList):
@@ -82,8 +82,8 @@ def eta(self):
8282
>>> e = ETS.ty()
8383
>>> e.eta
8484
85-
.. note:: If the value was given in degrees it will be converted to
86-
radians.
85+
.. note:: If the value was given in degrees it will be converted and
86+
stored internally in radians
8787
"""
8888
return self.data[0].eta
8989

@@ -255,7 +255,6 @@ def eval(self, q=None, unit='rad'):
255255
Example:
256256
257257
.. runblock:: pycon
258-
:linenos:
259258
260259
>>> from roboticstoolbox import ETS
261260
>>> e = ETS.rz() * ETS.tx(1) * ETS.rz() * ETS.tx(1)
@@ -280,11 +279,25 @@ def eval(self, q=None, unit='rad'):
280279

281280
def __str__(self):
282281
"""
283-
Pretty prints the ET. Will output angles in degrees
282+
Pretty prints the ETS
284283
285-
:return: The transformation matrix of the ET
284+
:return: Pretty printed ETS
286285
:rtype: str
287286
287+
Angular parameters are converted to degrees, except if they are
288+
symbolic.
289+
290+
Example:
291+
292+
.. runblock:: pycon
293+
294+
>>> from roboticstoolbox import ETS
295+
>>> from spatialmath.base import symbol
296+
>>> theta, d = symbol('theta, d')
297+
>>> e = ETS.rx(theta) * ETS.tx(2) * ETS.rx(45, 'deg') * ETS.ry(0.2) * ETS.ty(d)
298+
>>> str(e)
299+
300+
:SymPy: supported
288301
"""
289302
es = []
290303
joint = 0
@@ -297,15 +310,18 @@ def __str__(self):
297310

298311
if et.isjoint:
299312
if show_q:
300-
s = '%s(q%d)' % (et.axis, joint)
313+
s = f"{et.axis}(q{joint})"
301314
else:
302-
s = '%s()' % (et.axis,)
315+
s = f"{et.axis}()"
303316
joint += 1
304317
else:
305318
if et.isrevolute:
306-
s = '%s(%g)' % (et.axis, et.eta * 180 / np.pi)
319+
if issymbol(et.eta):
320+
s = f"{et.axis}({et.eta})"
321+
else:
322+
s = f"{et.axis}({et.eta * 180 / np.pi:.4g}°)"
307323
else:
308-
s = '%s(%g)' % (et.axis, et.eta)
324+
s = f"{et.axis}({et.eta})"
309325

310326
es.append(s)
311327

@@ -421,6 +437,7 @@ def rx(cls, eta=None, unit='rad'):
421437
angle, i.e. a revolute robot joint
422438
423439
:seealso: :func:`ETS`
440+
:SymPy: supported
424441
"""
425442
return cls(trotx, axis='Rx', eta=eta, unit=unit)
426443

@@ -442,7 +459,7 @@ def ry(cls, eta=None, unit='rad'):
442459
angle, i.e. a revolute robot joint
443460
444461
:seealso: :func:`ETS`
445-
462+
:SymPy: supported
446463
"""
447464
return cls(troty, axis='Ry', eta=eta, unit=unit)
448465

@@ -464,6 +481,7 @@ def rz(cls, eta=None, unit='rad'):
464481
angle, i.e. a revolute robot joint
465482
466483
:seealso: :func:`ETS`
484+
:SymPy: supported
467485
"""
468486
return cls(trotz, axis='Rz', eta=eta, unit=unit)
469487

@@ -483,6 +501,7 @@ def tx(cls, eta=None):
483501
variable distance, i.e. a prismatic robot joint
484502
485503
:seealso: :func:`ETS`
504+
:SymPy: supported
486505
"""
487506

488507
# this method is 3x faster than using lambda x: transl(x, 0, 0)
@@ -512,7 +531,7 @@ def ty(cls, eta=None):
512531
variable distance, i.e. a prismatic robot joint
513532
514533
:seealso: :func:`ETS`
515-
534+
:SymPy: supported
516535
"""
517536
def axis_func(eta):
518537
return np.array([
@@ -542,6 +561,7 @@ def tz(cls, eta=None):
542561
variable distance, i.e. a prismatic robot joint
543562
544563
:seealso: :func:`ETS`
564+
:SymPy: supported
545565
"""
546566
def axis_func(eta):
547567
return np.array([
@@ -569,6 +589,13 @@ def axis_func(eta):
569589
print(e.eval([90, -90], 'deg'))
570590
a = e.pop()
571591
print(a)
592+
593+
from spatialmath.base import symbol
594+
595+
theta, d = symbol('theta, d')
596+
597+
e = ETS.rx(theta) * ETS.tx(2) * ETS.rx(45, 'deg') * ETS.ry(0.2) * ETS.ty(d)
598+
print(e)
572599

573600
# l1 = 0.672
574601
# l2 = -0.2337

0 commit comments

Comments
 (0)