@@ -1247,81 +1247,81 @@ def jacob_dot(self, q=None, qd=None):
1247
1247
1248
1248
return Jdot
1249
1249
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
1311
1256
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
+ # """
1314
1314
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')
1325
1325
1326
1326
def teach (
1327
1327
self , q = None , block = True , limits = None ,
@@ -1338,11 +1338,11 @@ def teach(
1338
1338
autoscale, [x1, x2, y1, y2, z1, z2]
1339
1339
:type limits: ndarray(6)
1340
1340
: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
1342
1342
translates along (prismatic joint)
1343
1343
:type jointaxes: bool
1344
1344
: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,
1346
1346
green and blue to indicate the x, y, and z-axes.
1347
1347
:type eeframe: bool
1348
1348
:param shadow: (Plot Option) Plot a shadow of the robot in the x-y
@@ -1360,10 +1360,11 @@ def teach(
1360
1360
inital joint configuration is ``q``. The plot will autoscale with an
1361
1361
aspect ratio of 1.
1362
1362
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.
1364
1365
1365
- .. note::
1366
- - Program execution is blocked until the teach window is
1366
+ .. note::
1367
+ - Program execution is blocked until the teach window is
1367
1368
dismissed. If ``block=False`` the method is non-blocking but
1368
1369
you need to poll the window manager to ensure that the window
1369
1370
remains responsive.
@@ -1408,13 +1409,13 @@ def vellipse(self, q=None, opt='trans', centre=[0, 0, 0]):
1408
1409
- ``robot.vellipse()`` as above except the joint configuration is that
1409
1410
stored in the robot object.
1410
1411
1411
- .. note::
1412
+ .. note::
1412
1413
- 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
1414
1415
ellipsoid.
1415
1416
- By default the ellipsoid is drawn at the origin. The option
1416
1417
``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
1418
1419
end-effector position.
1419
1420
"""
1420
1421
@@ -1442,13 +1443,13 @@ def fellipse(self, q=None, opt='trans', centre=[0, 0, 0]):
1442
1443
- ``robot.fellipse()`` as above except the joint configuration is that
1443
1444
stored in the robot object.
1444
1445
1445
- .. note::
1446
+ .. note::
1446
1447
- 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
1448
1449
ellipsoid.
1449
1450
- By default the ellipsoid is drawn at the origin. The option
1450
1451
``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
1452
1453
end-effector position.
1453
1454
1454
1455
'''
@@ -1903,13 +1904,12 @@ def ikine_6s(self, T, config, _ikfunc):
1903
1904
theta = theta - self .offset
1904
1905
1905
1906
q [k , :] = theta
1906
-
1907
+
1907
1908
if q .shape [0 ] == 1 :
1908
1909
return q [0 ]
1909
1910
else :
1910
1911
return q
1911
1912
1912
-
1913
1913
# def ikine_6s(self, T, left=True, elbow_up=True, wrist_flip=False):
1914
1914
# """
1915
1915
# Analytical inverse kinematics
@@ -2495,7 +2495,6 @@ def cost(q, T, pweight, col, stiffness):
2495
2495
else :
2496
2496
return qt , success , err
2497
2497
2498
-
2499
2498
# def jacob0v(self, q=None):
2500
2499
# """
2501
2500
# Jv = jacob0v(q) is the spatial velocity Jacobian, at joint
@@ -2558,14 +2557,14 @@ def cost(q, T, pweight, col, stiffness):
2558
2557
2559
2558
# return Jv
2560
2559
2560
+
2561
2561
class SerialLink (DHRobot ):
2562
2562
def __init__ (self , * args , ** kwargs ):
2563
2563
print ('SerialLink is deprecated, use DHRobot instead' )
2564
2564
super ().__init__ (* args , ** kwargs )
2565
2565
2566
-
2567
2566
2568
- if __name__ == "__main__" :
2567
+ if __name__ == "__main__" : # pragma nocover
2569
2568
2570
2569
import roboticstoolbox as rtb
2571
2570
# import spatialmath.base.symbolic as sym
@@ -2575,7 +2574,7 @@ def __init__(self, *args, **kwargs):
2575
2574
# print(J)
2576
2575
# print(puma.manipulability(puma.qn))
2577
2576
# print(puma.manipulability(puma.qn, 'asada'))
2578
- #tw, T0 = puma.twists(puma.qz)
2577
+ # tw, T0 = puma.twists(puma.qz)
2579
2578
print (planar )
2580
2579
2581
2580
puma = rtb .models .DH .Puma560 ()
@@ -2593,4 +2592,4 @@ def __init__(self, *args, **kwargs):
2593
2592
print (puma )
2594
2593
print (puma .ets ())
2595
2594
2596
- print (puma .dyntable ())
2595
+ print (puma .dyntable ())
0 commit comments