Skip to content

Commit f5b188d

Browse files
committed
linted
1 parent b55a826 commit f5b188d

File tree

3 files changed

+49
-96
lines changed

3 files changed

+49
-96
lines changed

roboticstoolbox/examples/swift_benchmark.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,10 @@
2525
def stepper():
2626
for i in range(10000):
2727
panda.qd = np.linalg.pinv(panda.jacob0(panda.q, fast=True)) @ ev
28+
# panda.jacob0(panda.q, fast=True)
29+
2830
# panda.fkine_all_fast(panda.q)
2931
env.step(0.001)
3032

3133

32-
cProfile.run('stepper()')
34+
cProfile.run("stepper()")

roboticstoolbox/examples/tripleangle.py

Lines changed: 41 additions & 86 deletions
Original file line numberDiff line numberDiff line change
@@ -20,41 +20,39 @@
2020
env = swift.Swift()
2121
env.launch()
2222

23-
path = rtb.path_to_datafile('data')
23+
path = rtb.path_to_datafile("data")
2424

2525

2626
g1 = Mesh(
27-
filename=str(path / 'gimbal-ring1.stl'),
28-
color=[34, 143, 201],
29-
scale=(1. / 3,) * 3
27+
filename=str(path / "gimbal-ring1.stl"), color=[34, 143, 201], scale=(1.0 / 3,) * 3
3028
)
29+
g1.v = [0, 0, 0, 0, 0.5, 0]
3130

3231
g2 = Mesh(
33-
filename=str(path / 'gimbal-ring2.stl'),
34-
color=[31, 184, 72],
35-
scale=(1.1 / 3,) * 3
36-
32+
filename=str(path / "gimbal-ring2.stl"), color=[31, 184, 72], scale=(1.1 / 3,) * 3
3733
)
34+
g2.v = [0, 0, 0, 0.5, 0, 0]
3835

3936
g3 = Mesh(
40-
filename=str(path / 'gimbal-ring3.stl'),
37+
filename=str(path / "gimbal-ring3.stl"),
4138
color=[240, 103, 103],
42-
scale=(1.1**2 / 3,) * 3
39+
scale=(1.1 ** 2 / 3,) * 3,
4340
)
41+
g3.v = [0, 0, 0, 0, 0, 0.5]
4442

4543
plane = Mesh(
46-
filename=str(path / 'spitfire_assy-gear_up.stl'),
47-
scale=(1. / (180 * 3),) * 3,
48-
color=[240, 103, 103]
44+
filename=str(path / "spitfire_assy-gear_up.stl"),
45+
scale=(1.0 / (180 * 3),) * 3,
46+
color=[240, 103, 103],
4947
)
50-
print(path / 'spitfire_assy-gear_up.stl')
48+
print(path / "spitfire_assy-gear_up.stl")
5149
env.add(g1)
5250
env.add(g2)
5351
env.add(g3)
5452
env.add(plane)
5553

56-
print('Supermarine Spitfire Mk VIII by Ed Morley @GRABCAD')
57-
print('Gimbal models by Peter Corke using OpenSCAD')
54+
print("Supermarine Spitfire Mk VIII by Ed Morley @GRABCAD")
55+
print("Gimbal models by Peter Corke using OpenSCAD")
5856

5957
# compute the three rotation matrices
6058
BASE = SE3(0, 0, 0.5)
@@ -72,11 +70,11 @@ def update_gimbals(theta, ring):
7270
# update the relevant transform, depending on which ring's slider moved
7371
def Rxyz(theta, which):
7472
theta = np.radians(theta)
75-
if which == 'X':
73+
if which == "X":
7674
return SO3.Rx(theta)
77-
elif which == 'Y':
75+
elif which == "Y":
7876
return SO3.Ry(theta)
79-
elif which == 'Z':
77+
elif which == "Z":
8078
return SO3.Rz(theta)
8179

8280
if ring == 1:
@@ -111,46 +109,32 @@ def set_three(x):
111109

112110

113111
r_one = swift.Slider(
114-
set_one,
115-
min=-180, max=180,
116-
step=1, value=0,
117-
desc='Outer gimbal', unit='°')
112+
set_one, min=-180, max=180, step=1, value=0, desc="Outer gimbal", unit="°"
113+
)
118114

119115

120116
r_two = swift.Slider(
121-
set_two,
122-
min=-180, max=180,
123-
step=1, value=0,
124-
desc='Middle gimbal', unit='°')
117+
set_two, min=-180, max=180, step=1, value=0, desc="Middle gimbal", unit="°"
118+
)
125119

126120

127121
r_three = swift.Slider(
128-
set_three,
129-
min=-180, max=180,
130-
step=1, value=0,
131-
desc='Inner gimbal', unit='°')
122+
set_three, min=-180, max=180, step=1, value=0, desc="Inner gimbal", unit="°"
123+
)
132124

133125

134126
# buttons to set a 3-angle sequence
135127
ZYX_button = swift.Button(
136-
lambda x: change_sequence('ZYX'),
137-
desc='ZYX (roll-pitch-yaw angles)'
128+
lambda x: change_sequence("ZYX"), desc="ZYX (roll-pitch-yaw angles)"
138129
)
139130

140131
XYZ_button = swift.Button(
141-
lambda x: change_sequence('XYZ'),
142-
desc='XYZ (roll-pitch-yaw angles)'
132+
lambda x: change_sequence("XYZ"), desc="XYZ (roll-pitch-yaw angles)"
143133
)
144134

145-
ZYZ_button = swift.Button(
146-
lambda x: change_sequence('ZYZ'),
147-
desc='ZYZ (Euler angles)'
148-
)
135+
ZYZ_button = swift.Button(lambda x: change_sequence("ZYZ"), desc="ZYZ (Euler angles)")
149136

150-
button = swift.Button(
151-
lambda x: set('ZYX'),
152-
desc='Set to Zero'
153-
)
137+
button = swift.Button(lambda x: set("ZYX"), desc="Set to Zero")
154138

155139

156140
# button to reset joint angles
@@ -161,10 +145,7 @@ def reset(e):
161145
# env.step(0)
162146

163147

164-
zero_button = swift.Button(
165-
reset,
166-
desc='Set to Zero'
167-
)
148+
zero_button = swift.Button(reset, desc="Set to Zero")
168149

169150

170151
def update_all_sliders():
@@ -176,7 +157,7 @@ def update_all_sliders():
176157
def change_sequence(new):
177158
global sequence
178159

179-
xyz = 'XYZ'
160+
xyz = "XYZ"
180161

181162
# update the state of the ring_axis dropdowns
182163
ring1_axis.checked = xyz.find(new[0])
@@ -192,62 +173,36 @@ def angle(index, ring):
192173
global sequence
193174

194175
# print('angle', index, ring)
195-
xyz = 'XYZ'
176+
xyz = "XYZ"
196177
s = list(sequence)
197178
s[ring] = xyz[int(index)]
198-
sequence = ''.join(s)
179+
sequence = "".join(s)
199180
update_all_sliders()
200181

201182

202-
ring1_axis = swift.Radio(
203-
lambda x: angle(x, 0),
204-
options=[
205-
'X',
206-
'Y',
207-
'Z'
208-
],
209-
checked=2
210-
)
183+
ring1_axis = swift.Radio(lambda x: angle(x, 0), options=["X", "Y", "Z"], checked=2)
211184

212-
ring2_axis = swift.Radio(
213-
lambda x: angle(x, 1),
214-
options=[
215-
'X',
216-
'Y',
217-
'Z'
218-
],
219-
checked=1
220-
)
185+
ring2_axis = swift.Radio(lambda x: angle(x, 1), options=["X", "Y", "Z"], checked=1)
221186

222-
ring3_axis = swift.Radio(
223-
lambda x: angle(x, 2),
224-
options=[
225-
'X',
226-
'Y',
227-
'Z'
228-
],
229-
checked=0
230-
)
187+
ring3_axis = swift.Radio(lambda x: angle(x, 2), options=["X", "Y", "Z"], checked=0)
231188

232189

233-
label = swift.Label(
234-
desc='Triple angle'
235-
)
190+
label = swift.Label(desc="Triple angle")
236191

237192

238193
def chekked(e, el):
239-
nlabel = 's: '
194+
nlabel = "s: "
240195

241196
if e[0]:
242-
nlabel += 'a'
197+
nlabel += "a"
243198
r_one.value = 0
244199

245200
if e[1]:
246-
nlabel += 'b'
201+
nlabel += "b"
247202
r_two.value = 0
248203

249204
if e[2]:
250-
nlabel += 'c'
205+
nlabel += "c"
251206
r_three.value = 0
252207

253208
if e[3]:
@@ -275,5 +230,5 @@ def chekked(e, el):
275230
update_gimbals(0, 2)
276231
update_gimbals(0, 3)
277232

278-
while(True):
279-
env.step(0)
233+
while True:
234+
env.step(0.05)

roboticstoolbox/models/URDF/PR2.py

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -5,27 +5,23 @@
55

66

77
class PR2(ERobot):
8-
98
def __init__(self):
109

1110
links, name = self.URDF_read(
12-
"pr2_description/robots/pr2.urdf.xacro",
13-
"pr2_description")
11+
"pr2_description/robots/pr2.urdf.xacro", "pr2_description"
12+
)
1413

15-
super().__init__(
16-
links,
17-
gripper_links=[links[53], links[73]],
18-
name=name)
14+
super().__init__(links, gripper_links=[links[53], links[73]], name=name)
1915

2016
self.grippers[0].tool = self.link_dict["r_gripper_tool_frame"].A()
2117
self.grippers[1].tool = self.link_dict["l_gripper_tool_frame"].A()
2218

23-
self.manufacturer = 'Willow Garage'
19+
self.manufacturer = "Willow Garage"
2420

2521
self.qz = np.zeros(31)
2622

2723

28-
if __name__ == '__main__': # pragma nocover
24+
if __name__ == "__main__": # pragma nocover
2925

3026
r = PR2()
3127

0 commit comments

Comments
 (0)