Skip to content

Commit aae4956

Browse files
committed
remove end ';'
1 parent 9b51de3 commit aae4956

37 files changed

+563
-563
lines changed

demo/animation.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
# the overloaded function plot() animates a stick figure robot moving
1313
# along a trajectory.
1414

15-
plot(p560, q);
15+
plot(p560, q)
1616
# The drawn line segments do not necessarily correspond to robot links, but
1717
# join the origins of sequential link coordinate frames.
1818
#
@@ -28,18 +28,18 @@
2828
#
2929
# Let's make a clone of the Puma robot, but change its name and base location
3030

31-
p560_2 = p560;
32-
p560_2.name = 'another Puma';
33-
p560_2.base = transl(-0.5, 0.5, 0);
31+
p560_2 = p560
32+
p560_2.name = 'another Puma'
33+
p560_2.base = transl(-0.5, 0.5, 0)
3434
hold on
35-
plot(p560_2, q);
35+
plot(p560_2, q)
3636
pause % any key to continue
3737

3838
# We can also have multiple views of the same robot
3939
clf
40-
plot(p560, qr);
40+
plot(p560, qr)
4141
figure
42-
plot(p560, qr);
42+
plot(p560, qr)
4343
view(40,50)
4444
plot(p560, q)
4545
pause % any key to continue

demo/fdyn.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,21 +30,21 @@
3030
# To simulate the motion of the Puma 560 from rest in the zero angle pose
3131
# with zero applied joint torques
3232
tic
33-
[t q qd] = fdyn(nofriction(p560), 0, 10);
33+
[t q qd] = fdyn(nofriction(p560), 0, 10)
3434
toc
3535
#
3636
# and the resulting motion can be plotted versus time
3737
subplot(3,1,1)
3838
plot(t,q(:,1))
39-
xlabel('Time (s)');
39+
xlabel('Time (s)')
4040
ylabel('Joint 1 (rad)')
4141
subplot(3,1,2)
4242
plot(t,q(:,2))
43-
xlabel('Time (s)');
43+
xlabel('Time (s)')
4444
ylabel('Joint 2 (rad)')
4545
subplot(3,1,3)
4646
plot(t,q(:,3))
47-
xlabel('Time (s)');
47+
xlabel('Time (s)')
4848
ylabel('Joint 3 (rad)')
4949
#
5050
# Clearly the robot is collapsing under gravity, but it is interesting to

demo/fkine.py

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
# references, clarification of functions.
1111
#
1212

13-
import robot.parsedemo as p;
13+
import robot.parsedemo as p
1414
import sys
1515

1616
print sys.modules
@@ -45,7 +45,7 @@
4545
(q, qd, qdd) = jtraj(qz, qr, t); % compute the joint coordinate trajectory
4646
#
4747
# then the homogeneous transform for each set of joint coordinates is given by
48-
T = fkine(p560, q);
48+
T = fkine(p560, q)
4949
5050
#
5151
# where T is a list of matrices.
@@ -60,33 +60,33 @@
6060
# Elements (0:2,3) correspond to the X, Y and Z coordinates respectively, and
6161
# may be plotted against time
6262
x = array([e[0,3] for e in T])
63-
y = array([e[1,3] for e in T]);
64-
z = array([e[2,3] for e in T]);
65-
subplot(3,1,1);
66-
plot(t, x);
67-
xlabel('Time (s)');
68-
ylabel('X (m)');
69-
subplot(3,1,2);
70-
plot(t, y);
71-
xlabel('Time (s)');
72-
ylabel('Y (m)');
73-
subplot(3,1,3);
74-
plot(t, z);
75-
xlabel('Time (s)');
76-
ylabel('Z (m)');
63+
y = array([e[1,3] for e in T])
64+
z = array([e[2,3] for e in T])
65+
subplot(3,1,1)
66+
plot(t, x)
67+
xlabel('Time (s)')
68+
ylabel('X (m)')
69+
subplot(3,1,2)
70+
plot(t, y)
71+
xlabel('Time (s)')
72+
ylabel('Y (m)')
73+
subplot(3,1,3)
74+
plot(t, z)
75+
xlabel('Time (s)')
76+
ylabel('Z (m)')
7777
show()
7878
pause % any key to continue
7979
#
8080
# or we could plot X against Z to get some idea of the Cartesian path followed
8181
# by the manipulator.
8282
#
83-
clf();
84-
plot(x, z);
85-
xlabel('X (m)');
86-
ylabel('Z (m)');
87-
grid();
83+
clf()
84+
plot(x, z)
85+
xlabel('X (m)')
86+
ylabel('Z (m)')
87+
grid()
8888
pause % any key to continue
8989
echo off
9090
'''
9191

92-
p.parsedemo(s);
92+
p.parsedemo(s)

demo/idyn.py

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
import robot.parsedemo as p;
1+
import robot.parsedemo as p
22
import sys
33

44
print sys.modules
@@ -34,32 +34,32 @@
3434
tau = rne(p560, q, qd, qdd); % compute inverse dynamics
3535
#
3636
# Now the joint torques can be plotted as a function of time
37-
plot(t, tau[:,0:2]);
38-
xlabel('Time (s)');
39-
ylabel('Joint torque (Nm)');
37+
plot(t, tau[:,0:2])
38+
xlabel('Time (s)')
39+
ylabel('Joint torque (Nm)')
4040
show()
4141
4242
#
4343
# Much of the torque on joints 2 and 3 of a Puma 560 (mounted conventionally) is
4444
# due to gravity. That component can be computed using gravload()
45-
clf();
46-
taug = gravload(p560, q);
47-
plot(t, taug[:,0:2]);
48-
xlabel('Time (s)');
49-
ylabel('Gravity torque (Nm)');
45+
clf()
46+
taug = gravload(p560, q)
47+
plot(t, taug[:,0:2])
48+
xlabel('Time (s)')
49+
ylabel('Gravity torque (Nm)')
5050
show()
5151
5252
# Now lets plot that as a fraction of the total torque required over the
5353
# trajectory
54-
clf();
55-
subplot(2,1,1);
56-
plot(t, hstack((tau[:,1], taug[:,1])));
57-
xlabel('Time (s)');
58-
ylabel('Torque on joint 2 (Nm)');
59-
subplot(2,1,2);
60-
plot(t, hstack((tau[:,2], taug[:,2])));
61-
xlabel('Time (s)');
62-
ylabel('Torque on joint 3 (Nm)');
54+
clf()
55+
subplot(2,1,1)
56+
plot(t, hstack((tau[:,1], taug[:,1])))
57+
xlabel('Time (s)')
58+
ylabel('Torque on joint 2 (Nm)')
59+
subplot(2,1,2)
60+
plot(t, hstack((tau[:,2], taug[:,2])))
61+
xlabel('Time (s)')
62+
ylabel('Torque on joint 3 (Nm)')
6363
pause % any key to continue
6464
#
6565
# The inertia seen by the waist (joint 1) motor changes markedly with robot
@@ -68,11 +68,11 @@
6868
#
6969
# Let's compute the variation in joint 1 inertia, that is M(1,1), as the
7070
# manipulator moves along the trajectory (this may take a few seconds)
71-
M = inertia(p560, q);
72-
M11 = array([m[0,0] for m in M]);
73-
clf();
74-
plot(t, M11);
75-
xlabel('Time (s)');
71+
M = inertia(p560, q)
72+
M11 = array([m[0,0] for m in M])
73+
clf()
74+
plot(t, M11)
75+
xlabel('Time (s)')
7676
ylabel('Inertia on joint 1 (kgms2)')
7777
# Clearly the inertia seen by joint 1 varies considerably over this path.
7878
# This is one of many challenges to control design in robotics, achieving
@@ -82,4 +82,4 @@
8282
pause
8383
'''
8484

85-
p.parsedemo(s);
85+
p.parsedemo(s)

demo/ikine.py

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
# Copyright (C) 1993-2002, by Peter I. Corke
22

33

4-
import robot.parsedemo as p;
4+
import robot.parsedemo as p
55
import sys
66

77

@@ -18,7 +18,7 @@
1818
#
1919
# First generate the transform corresponding to a particular joint coordinate,
2020
q = mat([0, -pi/4, -pi/4, 0, pi/8, 0])
21-
T = fkine(p560, q);
21+
T = fkine(p560, q)
2222
#
2323
# Now the inverse kinematic procedure for any specific robot can be derived
2424
# symbolically and in general an efficient closed-form solution can be
@@ -29,7 +29,7 @@
2929
# have several poses which result in the same transform for the last
3030
# link. The starting point for the first point may be specified, or else it
3131
# defaults to zero (which is not a particularly good choice in this case)
32-
qi = ikine(p560, T);
32+
qi = ikine(p560, T)
3333
qi.T
3434
#
3535
# Compared with the original value
@@ -45,8 +45,8 @@
4545
# To examine the effect at a singularity lets repeat the last example but for a
4646
# different pose. At the `ready' position two of the Puma's wrist axes are
4747
# aligned resulting in the loss of one degree of freedom.
48-
T = fkine(p560, qr);
49-
qi = ikine(p560, T);
48+
T = fkine(p560, qr)
49+
qi = ikine(p560, T)
5050
qi.T
5151
#
5252
# which is not the same as the original joint angle
@@ -76,19 +76,19 @@
7676
#
7777
# Let's examine the joint space trajectory that results in straightline
7878
# Cartesian motion
79-
subplot(3,1,1);
80-
plot(t,q[:,1]);
81-
xlabel('Time (s)');
82-
ylabel('Joint 1 (rad)');
83-
subplot(3,1,2);
84-
plot(t,q[:,2]);
85-
xlabel('Time (s)');
86-
ylabel('Joint 2 (rad)');
87-
subplot(3,1,3);
88-
plot(t,q[:,3]);
89-
xlabel('Time (s)');
90-
ylabel('Joint 3 (rad)');
91-
show();
79+
subplot(3,1,1)
80+
plot(t,q[:,1])
81+
xlabel('Time (s)')
82+
ylabel('Joint 1 (rad)')
83+
subplot(3,1,2)
84+
plot(t,q[:,2])
85+
xlabel('Time (s)')
86+
ylabel('Joint 2 (rad)')
87+
subplot(3,1,3)
88+
plot(t,q[:,3])
89+
xlabel('Time (s)')
90+
ylabel('Joint 3 (rad)')
91+
show()
9292
pause % hit any key to continue
9393
9494
# This joint space trajectory can now be animated
@@ -97,4 +97,4 @@
9797
#pause % any key to continue
9898
'''
9999

100-
p.parsedemo(s);
100+
p.parsedemo(s)

demo/jacobian.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11

2-
import robot.parsedemo as p;
2+
import robot.parsedemo as p
33
import sys
44

55

@@ -20,18 +20,18 @@
2020
#
2121
# but a more direct approach is to use the function diff2tr()
2222
#
23-
D = mat([.1, .2, 0, -.2, .1, .1]).T;
23+
D = mat([.1, .2, 0, -.2, .1, .1]).T
2424
skew(D)
2525
pause % any key to continue
2626
#
2727
# More commonly it is useful to know how a differential motion in one
2828
# coordinate frame appears in another frame. If the second frame is
2929
# represented by the transform
30-
T = transl(100, 200, 300) * troty(pi/8) * trotz(-pi/4);
30+
T = transl(100, 200, 300) * troty(pi/8) * trotz(-pi/4)
3131
#
3232
# then the differential motion in the second frame would be given by
3333
34-
DT = tr2jac(T) * D;
34+
DT = tr2jac(T) * D
3535
DT.T
3636
#
3737
# tr2jac() has computed a 6x6 Jacobian matrix which transforms the differential
@@ -40,7 +40,7 @@
4040
pause % any key to continue
4141
4242
# The manipulator's Jacobian matrix relates differential joint coordinate
43-
# motion to differential Cartesian motion;
43+
# motion to differential Cartesian motion
4444
#
4545
# dX = J(q) dQ
4646
#
@@ -83,10 +83,10 @@
8383
# joint velocity to achieve this.
8484
#
8585
# We demand pure translational motion in the X direction
86-
vel = mat([1, 0, 0, 0, 0, 0]).T;
86+
vel = mat([1, 0, 0, 0, 0, 0]).T
8787
8888
# and "resolve" this into joint rates
89-
qvel = Ji * vel;
89+
qvel = Ji * vel
9090
qvel.T
9191
#
9292
# This is an alternative strategy to computing a Cartesian trajectory
@@ -152,4 +152,4 @@
152152
#
153153
'''
154154

155-
p.parsedemo(s);
155+
p.parsedemo(s)

0 commit comments

Comments
 (0)