@@ -24,16 +24,27 @@ def make_transparent(link):
24
24
for link in visual_data :
25
25
make_transparent (link )
26
26
27
-
28
- def test_jacobian_follower ():
27
+ def create_test_chain (robot = "kuka_iiwa" , device = "cpu" ):
28
+ if robot == "kuka_iiwa" :
29
+ urdf = "kuka_iiwa/model.urdf"
30
+ search_path = pybullet_data .getDataPath ()
31
+ full_urdf = os .path .join (search_path , urdf )
32
+ chain = pk .build_serial_chain_from_urdf (open (full_urdf ).read (), "lbr_iiwa_link_7" )
33
+ chain = chain .to (device = device )
34
+ elif robot == "widowx" :
35
+ urdf = "widowx/wx250s.urdf"
36
+ full_urdf = urdf
37
+ chain = pk .build_serial_chain_from_urdf (open (full_urdf , "rb" ).read (), "ee_gripper_link" )
38
+ chain = chain .to (device = device )
39
+ else :
40
+ raise NotImplementedError (f"Robot { robot } not implemented" )
41
+ return chain , urdf
42
+
43
+ def test_jacobian_follower (robot = "kuka_iiwa" ):
29
44
pytorch_seed .seed (2 )
30
45
device = "cuda" if torch .cuda .is_available () else "cpu"
31
- # device = "cpu"
32
- urdf = "kuka_iiwa/model.urdf"
33
46
search_path = pybullet_data .getDataPath ()
34
- full_urdf = os .path .join (search_path , urdf )
35
- chain = pk .build_serial_chain_from_urdf (open (full_urdf ).read (), "lbr_iiwa_link_7" )
36
- chain = chain .to (device = device )
47
+ chain , urdf = create_test_chain (robot = robot , device = device )
37
48
38
49
# robot frame
39
50
pos = torch .tensor ([0.0 , 0.0 , 0.0 ], device = device )
@@ -45,7 +56,7 @@ def test_jacobian_follower():
45
56
# generate random goal joint angles (so these are all achievable)
46
57
# use the joint limits to generate random joint angles
47
58
lim = torch .tensor (chain .get_joint_limits (), device = device )
48
- goal_q = torch .rand (M , 7 , device = device ) * (lim [1 ] - lim [0 ]) + lim [0 ]
59
+ goal_q = torch .rand (M , lim . shape [ 1 ] , device = device ) * (lim [1 ] - lim [0 ]) + lim [0 ]
49
60
50
61
# get ee pose (in robot frame)
51
62
goal_in_rob_frame_tf = chain .forward_kinematics (goal_q )
@@ -159,24 +170,19 @@ def test_jacobian_follower():
159
170
p .stepSimulation ()
160
171
161
172
162
- def test_ik_in_place_no_err ():
173
+ def test_ik_in_place_no_err (robot = "kuka_iiwa" ):
163
174
pytorch_seed .seed (2 )
164
175
device = "cuda" if torch .cuda .is_available () else "cpu"
165
176
# device = "cpu"
166
- urdf = "kuka_iiwa/model.urdf"
167
- search_path = pybullet_data .getDataPath ()
168
- full_urdf = os .path .join (search_path , urdf )
169
- chain = pk .build_serial_chain_from_urdf (open (full_urdf ).read (), "lbr_iiwa_link_7" )
170
- chain = chain .to (device = device )
171
-
177
+ chain , urdf = create_test_chain (robot = robot , device = device )
172
178
# robot frame
173
179
pos = torch .tensor ([0.0 , 0.0 , 0.0 ], device = device )
174
180
rot = torch .tensor ([0.0 , 0.0 , 0.0 ], device = device )
175
181
rob_tf = pk .Transform3d (pos = pos , rot = rot , device = device )
176
182
177
183
# goal equal to current configuration
178
184
lim = torch .tensor (chain .get_joint_limits (), device = device )
179
- cur_q = torch .rand (7 , device = device ) * (lim [1 ] - lim [0 ]) + lim [0 ]
185
+ cur_q = torch .rand (lim . shape [ 1 ] , device = device ) * (lim [1 ] - lim [0 ]) + lim [0 ]
180
186
M = 1
181
187
goal_q = cur_q .unsqueeze (0 ).repeat (M , 1 )
182
188
@@ -209,5 +215,9 @@ def test_ik_in_place_no_err():
209
215
210
216
211
217
if __name__ == "__main__" :
212
- test_jacobian_follower ()
213
- test_ik_in_place_no_err ()
218
+ print ("Testing kuka_iiwa IK" )
219
+ test_jacobian_follower (robot = "kuka_iiwa" )
220
+ test_ik_in_place_no_err (robot = "kuka_iiwa" )
221
+ print ("Testing widowx IK" )
222
+ test_jacobian_follower (robot = "widowx" )
223
+ test_ik_in_place_no_err (robot = "widowx" )
0 commit comments