8000 pyplot · A905275/robotics-toolbox-python@ce41848 · GitHub
[go: up one dir, main page]

Skip to content
8000

Commit ce41848

Browse files
committed
pyplot
1 parent f124942 commit ce41848

File tree

5 files changed

+155
-122
lines changed

5 files changed

+155
-122
lines changed

examples/plot_swift.py

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
#!/usr/bin/env python
2+
"""
3+
@author Jesse Haviland
4+
"""
5+
6+
import roboticstoolbox as rp
7+
import spatialmath as sm
8+
import numpy as np
9+
10+
panda = rp.models.DH.Panda()
11+
12+
panda.plot()

roboticstoolbox/backends/PyPlot/functions.py

Lines changed: 19 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
import time
77
import roboticstoolbox as rp
88
import numpy as np
9-
from spatialmath.base.argcheck import getvector, getmatrix
9+
from spatialmath.base.argcheck import getmatrix
1010
from roboticstoolbox.backends.PyPlot.EllipsePlot import EllipsePlot
1111
from matplotlib.widgets import Slider
1212
try:
@@ -26,7 +26,6 @@ def _plot(
2626

2727
q = getmatrix(q, (None, robot.n))
2828

29-
3029
# Add the robot to the figure in readonly mode
3130
if q.shape[0] == 1:
3231
env.launch(robot.name + ' Plot', limits)
@@ -47,30 +46,32 @@ def _plot(
4746

4847
if movie is not None:
4948
if not _pil_exists:
50-
raise RuntimeError('to save movies PIL must be installed:\npip3 install PIL')
49+
raise RuntimeError(
50+
'to save movies PIL must be installed:\npip3 install PIL')
5151
images = [] # list of images saved from each plot
5252
# make the background white, looks better than grey stipple
5353
env.ax.w_xaxis.set_pane_color((1.0, 1.0, 1.0, 1.0))
5454
env.ax.w_yaxis.set_pane_color((1.0, 1.0, 1.0, 1.0))
5555
env.ax.w_zaxis.set_pane_color((1.0, 1.0, 1.0, 1.0))
5656

5757
for qk in q:
58-
robot.q = qk
59-
env.step()
60-
#time.sleep(dt/1000)
61-
62-
if movie is not None:
63-
# render the frame and save as a PIL image in the list
64-
canvas = env.fig.canvas
65-
img = PIL.Image.frombytes('RGB', canvas.get_width_height(),
66-
canvas.tostring_rgb())
67-
images.append(img)
58+
robot.q = qk
59+
env.step()
60+
61+
if movie is not None:
62+
# render the frame and save as a PIL image in the list
63+
canvas = env.fig.canvas
64+
img = PIL.Image.frombytes(
65+
'RGB', canvas.get_width_height(),
66+
canvas.tostring_rgb())
67+
images.append(img)
6868

6969
if movie is not None:
7070
# save it as an animated GIF
71-
images[0].save(movie,
72-
save_all=True, append_images=images[1:], optimize=False,
73-
duration=dt, loop=0)
71+
images[0].save(
72+
movie,
73+
save_all=True, append_images=images[1:], optimize=False,
74+
duration=dt, loop=0)
7475

7576
# Keep the plot open
7677
if block: # pragma: no cover
@@ -329,7 +330,8 @@ def _plot_ellipse(
329330

330331
if not isinstance(ellipse, EllipsePlot):
331332
raise TypeError(
332-
'ellipse must be of type roboticstoolbox.backend.PyPlot.EllipsePlot')
333+
'ellipse must be of type '
334+
'roboticstoolbox.backend.PyPlot.EllipsePlot')
333335

334336
env = rp.backends.PyPlot()
335337

roboticstoolbox/robot/DHRobot.py

Lines changed: 90 additions & 91 deletions
Original file line numberDiff line numberDiff line change
@@ -1247,81 +1247,81 @@ def jacob_dot(self, q=None, qd=None):
12471247

12481248
return Jdot
12491249

1250-
def plot(
1251-
self, q=None, block=True, dt=0.050, limits=None,
1252-
vellipse=False, fellipse=False,
1253-
jointaxes=True, eeframe=True, shadow=True, name=True, movie=None):
1254-
"""
1255-
Graphical display and animation
1256-
1257-
:param block: Block operation of the code and keep the figure open
1258-
:type block: bool
1259-
:param q: The joint configuration of the robot (Optional,
1260-
if not supplied will use the stored q values).
1261-
:type q: float ndarray(n)
1262-
:param dt: if q is a trajectory, this describes the delay in
1263-
seconds between frames
1264-
:type dt: float
1265-
:param limits: Custom view limits for the plot. If not supplied will
1266-
autoscale, [x1, x2, y1, y2, z1, z2]
1267-
:type limits: ndarray(6)
1268-
:param vellipse: (Plot Option) Plot the velocity ellipse at the
1269-
end-effector
1270-
:type vellipse: bool
1271-
:param vellipse: (Plot Option) Plot the force ellipse at the
1272-
end-effector
1273-
:type vellipse: bool
1274-
:param jointaxes: (Plot Option) Plot an arrow indicating the axes in
1275-
which the joint revolves around(revolute joint) or translates
1276-
along (prosmatic joint)
1277-
:type jointaxes: bool
1278-
:param eeframe: (Plot Option) Plot the end-effector coordinate frame
1279-
at the location of the end-effector. Uses three arrows, red,
1280-
green and blue to indicate the x, y, and z-axes.
1281-
:type eeframe: bool
1282-
:param shadow: (Plot Option) Plot a shadow of the robot in the x-y
1283-
plane
1284-
:type shadow: bool
1285-
:param name: (Plot Option) Plot the name of the robot near its base
1286-
:type name: bool
1287-
:param movie: name of file in which to save an animated GIF
1288-
:type movie: str
1289-
1290-
:return: A reference to the PyPlot object which controls the
1291-
matplotlib figure
1292-
:rtype: PyPlot
1293-
1294-
- ``robot.plot(q)`` displays a graphical view of a robot based on the
1295-
kinematic model and the joint configuration ``q``. This is a stick
1296-
figure polyline which joins the origins of the link coordinate frames.
1297-
The plot will autoscale with an aspect ratio of 1.
1298-
1299-
- ``robot.plot()`` as above but use the stored ``q`` value.
1300-
1301-
If ``q`` (m,n) representing a joint-space trajectory it will create an
1302-
animation with a pause of ``dt`` seconds between each frame.
1303-
1304-
.. note::
1305-
- By default this method will block until the figure is dismissed.
1306-
To avoid this set ``block=False``.
1307-
- The polyline joins the origins of the link frames, but for
1308-
some Denavit-Hartenberg models those frames may not actually
1309-
be on the robot, ie. the lines to not neccessarily represent
1310-
the links of the robot.
1250+
# def plot(
1251+
# self, q=None, block=True, dt=0.050, limits=None,
1252+
# vellipse=False, fellipse=False,
1253+
# jointaxes=True, eeframe=True, shadow=True, name=True, movie=None):
1254+
# """
1255+
# Graphical display and animation
13111256

1312-
:seealso: :func:`teach`
1313-
"""
1257+
# :param block: Block operation of the code and keep the figure open
1258+
# :type block: bool
1259+
# :param q: The joint configuration of the robot (Optional,
1260+
# if not supplied will use the stored q values).
1261+
# :type q: float ndarray(n)
1262+
# :param dt: if q is a trajectory, this describes the delay in
1263+
# seconds between frames
1264+
# :type dt: float
1265+
# :param limits: Custom view limits for the plot. If not supplied will
1266+
# autoscale, [x1, x2, y1, y2, z1, z2]
1267+
# :type limits: ndarray(6)
1268+
# :param vellipse: (Plot Option) Plot the velocity ellipse at the
1269+
# end-effector
1270+
# :type vellipse: bool
1271+
# :param vellipse: (Plot Option) Plot the force ellipse at the
1272+
# end-effector
1273+
# :type vellipse: bool
1274+
# :param jointaxes: (Plot Option) Plot an arrow indicating the axes in
1275+
# which the joint revolves around(revolute joint) or translates
1276+
# along (prosmatic joint)
1277+
# :type jointaxes: bool
1278+
# :param eeframe: (Plot Option) Plot the end-effector coordinate frame
1279+
# at the location of the end-effector. Uses three arrows, red,
1280+
# green and blue to indicate the x, y, and z-axes.
1281+
# :type eeframe: bool
1282+
# :param shadow: (Plot Option) Plot a shadow of the robot in the x-y
1283+
# plane
1284+
# :type shadow: bool
1285+
# :param name: (Plot Option) Plot the name of the robot near its base
1286+
# :type name: bool
1287+
# :param movie: name of file in which to save an animated GIF
1288+
# :type movie: str
1289+
1290+
# :return: A reference to the PyPlot object which controls the
1291+
# matplotlib figure
1292+
# :rtype: PyPlot
1293+
1294+
# - ``robot.plot(q)`` displays a graphical view of a robot based on the
1295+
# kinematic model and the joint configuration ``q``. This is a stick
1296+
# figure polyline which joins the origins of the link coordinate
1297+
# frames. The plot will autoscale with an aspect ratio of 1.
1298+
1299+
# - ``robot.plot()`` as above but use the stored ``q`` value.
1300+
1301+
# If ``q`` (m,n) representing a joint-space trajectory it will create an
1302+
# animation with a pause of ``dt`` seconds between each frame.
1303+
1304+
# .. note::
1305+
# - By default this method will block until the figure is dismissed.
1306+
# To avoid this set ``block=False``.
1307+
# - The polyline joins the origins of the link frames, but for
1308+
# some Denavit-Hartenberg models those frames may not actually
1309+
# be on the robot, ie. the lines to not neccessarily represent
1310+
# the links of the robot.
1311+
1312+
# :seealso: :func:`teach`
1313+
# """
13141314

1315-
# try:
1316-
return _plot(
1317-
self, block, q, int(dt * 1000), limits,
1318-
vellipse=vellipse, fellipse=fellipse,
1319-
jointaxes=jointaxes, eeframe=eeframe, shadow=shadow, name=name,
1320-
movie=movie)
1321-
# except ModuleNotFoundError:
1322-
# print(
1323-
# 'Could not find matplotlib.'
1324-
# ' Matplotlib required for this function')
1315+
# # try:
1316+
# return _plot(
1317+
# self, block, q, int(dt * 1000), limits,
1318+
# vellipse=vellipse, fellipse=fellipse,
1319+
# jointaxes=jointaxes, eeframe=eeframe, shadow=shadow, name=name,
1320+
# movie=movie)
1321+
# # except ModuleNotFoundError:
1322+
# # print(
1323+
# # 'Could not find matplotlib.'
1324+
# # ' Matplotlib required for this function')
13251325

13261326
def teach(
13271327
self, q=None, block=True, limits=None,
@@ -1338,11 +1338,11 @@ def teach(
13381338
autoscale, [x1, x2, y1, y2, z1, z2]
13391339
:type limits: ndarray(6)
13401340
:param jointaxes: (Plot Option) Plot an arrow indicating the axes in
1341-
which the joint revolves around(revolute joint) or
1341+
which the joint revolves around(revolute joint) or
13421342
translates along (prismatic joint)
13431343
:type jointaxes: bool
13441344
:param eeframe: (Plot Option) Plot the end-effector coordinate frame
1345-
at the location of the end-effector. Uses three arrows, red,
1345+
at the location of the end-effector. Uses three arrows, red,
13461346
green and blue to indicate the x, y, and z-axes.
13471347
:type eeframe: bool
13481348
:param shadow: (Plot Option) Plot a shadow of the robot in the x-y
@@ -1360,10 +1360,11 @@ def teach(
13601360
inital joint configuration is ``q``. The plot will autoscale with an
13611361
aspect ratio of 1.
13621362
1363-
- ``robot.teach()`` as above except the robot's stored value of ``q`` is used.
1363+
- ``robot.teach()`` as above except the robot's stored value of ``q``
1364+
is used.
13641365
1365-
.. note::
1366-
- Program execution is blocked until the teach window is
1366+
.. note::
1367+
- Program execution is blocked until the teach window is
13671368
dismissed. If ``block=False`` the method is non-blocking but
13681369
you need to poll the window manager to ensure that the window
13691370
remains responsive.
@@ -1408,13 +1409,13 @@ def vellipse(self, q=None, opt='trans', centre=[0, 0, 0]):
14081409
- ``robot.vellipse()`` as above except the joint configuration is that
14091410
stored in the robot object.
14101411
1411-
.. note::
1412+
.. note::
14121413
- By default the ellipsoid related to translational motion is
1413-
drawn. Use ``opt='rot'`` to draw the rotational velocity
1414+
drawn. Use ``opt='rot'`` to draw the rotational velocity
14141415
ellipsoid.
14151416
- By default the ellipsoid is drawn at the origin. The option
14161417
``centre`` allows its origin to set to set to the specified
1417-
3-vector, or the string "ee" ensures it is drawn at the
1418+
3-vector, or the string "ee" ensures it is drawn at the
14181419
end-effector position.
14191420
"""
14201421

@@ -1442,13 +1443,13 @@ def fellipse(self, q=None, opt='trans', centre=[0, 0, 0]):
14421443
- ``robot.fellipse()`` as above except the joint configuration is that
14431444
stored in the robot object.
14441445
1445-
.. note::
1446+
.. note::
14461447
- By default the ellipsoid related to translational motion is
1447-
drawn. Use ``opt='rot'`` to draw the rotational velocity
1448+
drawn. Use ``opt='rot'`` to draw the rotational velocity
14481449
ellipsoid.
14491450
- By default the ellipsoid is drawn at the origin. The option
14501451
``centre`` allows its origin to set to set to the specified
1451-
3-vector, or the string "ee" ensures it is drawn at the
1452+
3-vector, or the string "ee" ensures it is drawn at the
14521453
end-effector position.
14531454
14541455
'''
@@ -1903,13 +1904,12 @@ def ikine_6s(self, T, config, _ikfunc):
19031904
theta = theta - self.offset
19041905

19051906
q[k, :] = theta
1906-
1907+
19071908
if q.shape[0] == 1:
19081909
return q[0]
19091910
else:
19101911
return q
19111912

1912-
19131913
# def ikine_6s(self, T, left=True, elbow_up=True, wrist_flip=False):
19141914
# """
19151915
# Analytical inverse kinematics
@@ -2495,7 +2495,6 @@ def cost(q, T, pweight, col, stiffness):
24952495
else:
24962496
return qt, success, err
24972497

2498-
24992498
# def jacob0v(self, q=None):
25002499
# """
25012500
# Jv = jacob0v(q) is the spatial velocity Jacobian, at joint
@@ -2558,14 +2557,14 @@ def cost(q, T, pweight, col, stiffness):
25582557

25592558
# return Jv
25602559

2560+
25612561
class SerialLink(DHRobot):
25622562
def __init__(self, *args, **kwargs):
25632563
print('SerialLink is deprecated, use DHRobot instead')
25642564
super().__init__(*args, **kwargs)
25652565

2566-
25672566

2568-
if __name__ == "__main__":
2567+
if __name__ == "__main__": # pragma nocover
25692568

25702569
import roboticstoolbox as rtb
25712570
# import spatialmath.base.symbolic as sym
@@ -2575,7 +2574,7 @@ def __init__(self, *args, **kwargs):
25752574
# print(J)
25762575
# print(puma.manipulability(puma.qn))
25772576
# print(puma.manipulability(puma.qn, 'asada'))
2578-
#tw, T0 = puma.twists(puma.qz)
2577+
# tw, T0 = puma.twists(puma.qz)
25792578
print(planar)
25802579

25812580
puma = rtb.models.DH.Puma560()
@@ -2593,4 +2592,4 @@ def __init__(self, *args, **kwargs):
25932592
print(puma)
25942593
print(puma.ets())
25952594

2596-
print(puma.dyntable())
2595+
print(puma.dyntable())

roboticstoolbox/robot/ERobot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1831,12 +1831,12 @@ def collided(self, shape):
18311831
# jointaxes=jointaxes, eeframe=eeframe, shadow=shadow, name=name)
18321832

18331833

1834-
if __name__ == "__main__":
1834+
if __name__ == "__main__": # pragma nocover
18351835

18361836
import roboticstoolbox as rtb
18371837
np.set_printoptions(precision=4, suppress=True)
18381838

1839-
p=rtb.models.URDF.Panda()
1839+
p = rtb.models.URDF.Panda()
18401840
print(p[1].m)
18411841

18421842
# robot = rtb.models.ETS.Panda()

0 commit comments

Comments
 (0)
0