-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathinitial.py
1412 lines (1243 loc) · 64 KB
/
initial.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
import copy
import os
import glob
import json
import random
import trimesh
import open3d as o3d
import numpy as np
import pybullet
import pybullet_data
import pybullet_utils.transformations as trans
import threading
import time
try:
import tensorflow._api.v2.compat.v1 as tf
except:
print("no tensorflow. assume oracle mode.")
from contact_graspnet.contact_grasp_estimator import extract_point_clouds
from moviepy.editor import ImageSequenceClip
PICK_TARGETS = {
"blue block": None,
"red block": None,
"green block": None,
"yellow block": None,
}
STANDARD_COLORS = ["White"]
# STANDARD_COLORS = [
# "AliceBlue", "Chartreuse", "Aqua", "Aquamarine", "Azure", "Beige", "Bisque",
# "BlanchedAlmond", "BlueViolet", "BurlyWood", "CadetBlue", "AntiqueWhite",
# "Chocolate", "Coral", "CornflowerBlue", "Cornsilk", "Cyan",
# "DarkCyan", "DarkGoldenRod", "DarkGrey", "DarkKhaki", "DarkOrange",
# "DarkOrchid", "DarkSalmon", "DarkSeaGreen", "DarkTurquoise", "DarkViolet",
# "DeepPink", "DeepSkyBlue", "DodgerBlue", "FloralWhite",
# "ForestGreen", "Fuchsia", "Gainsboro", "GhostWhite", "Gold", "GoldenRod",
# "Salmon", "Tan", "HoneyDew", "HotPink", "Ivory", "Khaki",
# "Lavender", "LavenderBlush", "LawnGreen", "LemonChiffon", "LightBlue",
# "LightCoral", "LightCyan", "LightGoldenRodYellow", "LightGray", "LightGrey",
# "LightGreen", "LightPink", "LightSalmon", "LightSeaGreen", "LightSkyBlue",
# "LightSlateGray", "LightSlateGrey", "LightSteelBlue", "LightYellow", "Lime",
# "LimeGreen", "Linen", "Magenta", "MediumAquaMarine", "MediumOrchid",
# "MediumPurple", "MediumSeaGreen", "MediumSlateBlue", "MediumSpringGreen",
# "MediumTurquoise", "MediumVioletRed", "MintCream", "MistyRose", "Moccasin",
# "NavajoWhite", "OldLace", "Olive", "OliveDrab", "Orange",
# "Orchid", "PaleGoldenRod", "PaleGreen", "PaleTurquoise", "PaleVioletRed",
# "PapayaWhip", "PeachPuff", "Peru", "Pink", "Plum", "PowderBlue", "Purple",
# "RosyBrown", "RoyalBlue", "SaddleBrown", "Green", "SandyBrown",
# "SeaGreen", "SeaShell", "Sienna", "Silver", "SkyBlue", "SlateBlue",
# "SlateGray", "SlateGrey", "Snow", "SpringGreen", "SteelBlue", "GreenYellow",
# "Teal", "Thistle", "Tomato", "Turquoise", "Violet", "Wheat", "White",
# "WhiteSmoke", "Yellow", "YellowGreen"
# ]
COLORS = {
"blue": (78 / 255, 121 / 255, 167 / 255, 255 / 255),
"red": (255 / 255, 87 / 255, 89 / 255, 255 / 255),
"green": (89 / 255, 169 / 255, 79 / 255, 255 / 255),
"yellow": (237 / 255, 201 / 255, 72 / 255, 255 / 255),
}
PLACE_TARGETS = {
"blue block": None,
"red block": None,
"green block": None,
"yellow block": None,
"blue bowl": None,
"red bowl": None,
"green bowl": None,
"yellow bowl": None,
"top left corner": (-0.3 + 0.05, -0.2 - 0.05, 0),
"top right corner": (0.3 - 0.05, -0.2 - 0.05, 0),
"middle": (0, -0.5, 0),
"bottom left corner": (-0.3 + 0.05, -0.8 + 0.05, 0),
"bottom right corner": (0.3 - 0.05, -0.8 + 0.05, 0),
}
PIXEL_SIZE = 0.00267857
BOUNDS = np.float32([[-0.3, 0.3], [-0.8, -0.2], [0, 0.15]]) # X Y Z
class Robotiq2F85:
"""Gripper handling for Robotiq 2F85."""
def __init__(self, robot, tool):
self.robot = robot
self.tool = tool
pos = [0.1339999999999999, -0.49199999999872496, 0.5]
rot = pybullet.getQuaternionFromEuler([np.pi, 0, np.pi])
urdf = "robotiq_2f_85/robotiq_2f_85.urdf"
self.body = pybullet.loadURDF(urdf, pos, rot)
self.n_joints = pybullet.getNumJoints(self.body)
self.activated = False
# Connect gripper base to robot tool.
pybullet.createConstraint(self.robot, tool, self.body, 0, jointType=pybullet.JOINT_FIXED, jointAxis=[0, 0, 0],
parentFramePosition=[0, 0, 0], childFramePosition=[0, 0, -0.07],
childFrameOrientation=pybullet.getQuaternionFromEuler([0, 0, np.pi / 2]))
# Set friction coefficients for gripper fingers.
for i in range(self.n_joints):
pybullet.changeDynamics(self.body, i, lateralFriction=10.0, spinningFriction=1.0, rollingFriction=1.0,
frictionAnchor=True)
self.joint_name_dict = {}
for i in range(self.n_joints):
joint_info = pybullet.getJointInfo(self.body, i)
self.joint_name_dict[joint_info[1].decode('utf-8')] = joint_info[0]
pybullet.enableJointForceTorqueSensor(self.body, joint_info[0], 1)
# Start thread to handle additional gripper constraints.
self.motor_joint = 1
self.constraints_thread = threading.Thread(target=self.step)
self.constraints_thread.daemon = True
self.constraints_thread.start()
pybullet.changeDynamics(self.body, linkIndex=4, lateralFriction=0.8)
pybullet.changeDynamics(self.body, linkIndex=9, lateralFriction=0.8)
def list_joint_names(self):
num_joints = pybullet.getNumJoints(self.body)
for i in range(num_joints):
joint_info = pybullet.getJointInfo(self.body, i)
joint_id = joint_info[0]
joint_name = joint_info[1].decode('utf-8')
print(f"Joint ID: {joint_id}, Joint Name: {joint_name}")
# Control joint positions by enforcing hard contraints on gripper behavior.
# Set one joint as the open/close motor joint (other joints should mimic).
def step(self):
while True:
try:
currj = [pybullet.getJointState(self.body, i)[0] for i in range(self.n_joints)]
indj = [6, 3, 8, 5, 10]
targj = [currj[1], -currj[1], -currj[1], currj[1], currj[1]]
pybullet.setJointMotorControlArray(self.body, indj, pybullet.POSITION_CONTROL, targj,
positionGains=np.ones(5))
except:
return
time.sleep(0.001)
# Close gripper fingers.
def activate(self, target_position=None, target_control=False, max_torque=100, torque_control=False):
if target_control:
pybullet.setJointMotorControl2(self.body, self.motor_joint, pybullet.POSITION_CONTROL, targetVelocity=1,
force=10, targetPosition=target_position)
elif torque_control:
pybullet.setJointMotorControl2(self.body, self.motor_joint, pybullet.TORQUE_CONTROL, force=max_torque)
else:
pybullet.setJointMotorControl2(self.body, self.motor_joint, pybullet.VELOCITY_CONTROL, targetVelocity=0.8,
force=13)
self.activated = True
def stop(self):
pybullet.setJointMotorControl2(self.body, self.motor_joint, pybullet.VELOCITY_CONTROL, targetVelocity=0)
self.activated = False
# Open gripper fingers.
def release(self):
pybullet.setJointMotorControl2(self.body, self.motor_joint, pybullet.VELOCITY_CONTROL, targetVelocity=-1,
force=10)
self.activated = False
# If activated and object in gripper: check object contact.
# If activated and nothing in gripper: check gripper contact.
# If released: check proximity to surface (disabled).
def detect_contact(self):
obj, _, ray_frac = self.check_proximity()
if self.activated:
empty = self.grasp_width() < 0.01
cbody = self.body if empty else obj
if obj == self.body or obj == 0:
return False
return self.external_contact(cbody)
# else:
# return ray_frac < 0.14 or self.external_contact()
# Return if body is in contact with something other than gripper
def external_contact(self, body=None):
if body is None:
body = self.body
pts = pybullet.getContactPoints(bodyA=body)
pts = [pt for pt in pts if pt[2] != self.body]
return len(pts) > 0 # pylint: disable=g-explicit-length-test
def check_grasp(self):
while self.moving():
time.sleep(0.001)
success = self.grasp_width() > 0.01
return success
def grasp_width(self):
lpad = np.array(pybullet.getLinkState(self.body, 4)[0])
rpad = np.array(pybullet.getLinkState(self.body, 9)[0])
dist = np.linalg.norm(lpad - rpad) - 0.047813
return dist
def check_finger_force(self):
lpad_link_id = 4
rpad_link_id = 9
# Get contact points for the fingertip
lcontact_points = pybullet.getContactPoints(bodyA=self.body, linkIndexA=lpad_link_id)
rcontact_points = pybullet.getContactPoints(bodyA=self.body, linkIndexA=rpad_link_id)
# Calculate the total force on the fingertip
ltotal_force = sum([cp[9] for cp in lcontact_points])
rtotal_force = sum([cp[9] for cp in rcontact_points])
print(ltotal_force, rtotal_force)
return ltotal_force, rtotal_force
def check_proximity(self):
ee_pos = np.array(pybullet.getLinkState(self.robot, self.tool)[0])
tool_pos = np.array(pybullet.getLinkState(self.body, 0)[0])
vec = (tool_pos - ee_pos) / np.linalg.norm((tool_pos - ee_pos))
ee_targ = ee_pos + vec
ray_data = pybullet.rayTest(ee_pos, ee_targ)[0]
obj, link, ray_frac = ray_data[0], ray_data[1], ray_data[2]
return obj, link, ray_frac
# @markdown Gym-style environment code
class RearrangeEnv():
def __init__(self, pick_place_info, obj_path, graspnet_checkpoint=None, forward_passes=5):
self.dt = 1 / 480
self.sim_step = 0
self.pick_place_info = pick_place_info
self.graspnet_checkpoint = graspnet_checkpoint
if graspnet_checkpoint is not None:
import contact_graspnet.config_utils as config_utils
from contact_graspnet.contact_grasp_estimator import GraspEstimator
from contact_graspnet.visualization_utils import show_image, plot_grasp_img, maximize_score_and_z_alignment
global_config = config_utils.load_config(graspnet_checkpoint, batch_size=forward_passes,
arg_configs=[])
self.grasp_estimator = GraspEstimator(global_config)
self.grasp_estimator.build_network()
self.show_image = show_image
self.plot_grasp_img = plot_grasp_img
self.maximize_score_and_z_alignment = maximize_score_and_z_alignment
# Configure and start PyBullet.
# python3 -m pybullet_utils.runServer
# pybullet.connect(pybullet.SHARED_MEMORY) # pybullet.GUI for local GUI.
pybullet.connect(pybullet.GUI) # pybullet.GUI for local GUI.
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_GUI, 0)
pybullet.setPhysicsEngineParameter(enableFileCaching=0)
assets_path = os.path.dirname(os.path.abspath(""))
pybullet.setAdditionalSearchPath(assets_path)
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
pybullet.setTimeStep(self.dt)
# self.home_joints = (
# np.pi / 2, -np.pi / 2, np.pi / 2, -np.pi / 2, 3 * np.pi / 2, 0) # Joint angles: (J0, J1, J2, J3, J4, J5).
self.home_joints = (
np.pi * 3 / 4, -np.pi / 2, np.pi / 4, -np.pi / 3, 3 * np.pi / 2, 0) # Joint angles: (J0, J1, J2, J3, J4, J5).
self.home_ee_euler = (np.pi, 0, np.pi) # (RX, RY, RZ) rotation in Euler angles.
self.ee_link_id = 9 # Link ID of UR5 end effector.
self.tip_link_id = 10 # Link ID of gripper finger tips.
self.gripper = None
self.model_base = obj_path
def grasps_infer(self, obs, local_regions=True, filter_grasps=True, skip_border_objects=False, z_range=[0.2, 1.8],
forward_passes=1, mode='oracle'):
os.makedirs('grasp_results', exist_ok=True)
segmap, rgb, depth, cam_K, pc_full = obs['seg'], obs['vis'], obs['depth'], obs['cam_K'], obs['points_cam']
pc_full, pc_segments, pc_colors = extract_point_clouds(depth, cam_K, segmap=segmap,
rgb=rgb,
skip_border_objects=skip_border_objects,
z_range=z_range)
if mode == 'oracle':
return None, None, None, pc_segments
# Add ops to save and restore all the variables.
saver = tf.train.Saver(save_relative_paths=True)
# Create a session
config = tf.ConfigProto()
config.gpu_options.allow_growth = True
config.allow_soft_placement = True
sess = tf.Session(config=config)
# Load weights
self.grasp_estimator.load_weights(sess, saver, self.graspnet_checkpoint, mode='test')
print('Generating Grasps...')
# pred_grasps_cam{seg_id:[n,4x4]}, scores{seg_id:[n,1]}
pred_grasps_cam, scores, contact_pts, openings = self.grasp_estimator.predict_scene_grasps(sess, pc_full,
pc_segments=pc_segments,
local_regions=local_regions,
filter_grasps=filter_grasps,
forward_passes=forward_passes)
# Visualize results
self.show_image(rgb, segmap)
self.plot_grasp_img(rgb, segmap, pred_grasps_cam, scores, obs['cam_K'])
# visualize_grasps(pc_full, pred_grasps_cam, scores, plot_opencv_cam=True, pc_colors=pc_colors)
return pred_grasps_cam, scores, openings, pc_segments
def load_model_from_obj(self, cat, obj_path, scale, pos, ori):
obj = trimesh.load(obj_path)
min_point = obj.bounds[0]
y_min = min_point[1]
z_min = min_point[2]
if cat != 'tablespoon' and cat != 'teaspoon':
mass_origin = np.array([obj.centroid[0], obj.centroid[1], z_min]) * scale
else:
mass_origin = np.array([obj.centroid[0], y_min, obj.centroid[2]]) * scale
visualShapeId = pybullet.createVisualShape(shapeType=pybullet.GEOM_MESH,
fileName=obj_path, # Replace with your mesh file
visualFramePosition=[0, 0, 0],
meshScale=[scale, scale, scale])
collisionShapeId = pybullet.createCollisionShape(shapeType=pybullet.GEOM_MESH,
fileName=obj_path, # Replace with your mesh file
collisionFramePosition=[0, 0, 0],
meshScale=[scale, scale, scale])
multiBodyId = pybullet.createMultiBody(baseMass=0,
baseInertialFramePosition=mass_origin,
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=pos,
baseOrientation=ori,
useMaximalCoordinates=True)
pos_, ori_ = pybullet.getBasePositionAndOrientation(multiBodyId)
return multiBodyId
def reset_rearrange(self, id, use_ur5=True):
self.pybullet_id_dict = {}
self.description_list = []
self.rel_pose_dict = {}
self.target_pose_dict = {}
self.target_bbox_dict = {}
self.ini_pose_dict = {}
self.ini_bbox_dict = {}
self.use_ur5 = use_ur5
pybullet.resetSimulation(pybullet.RESET_USE_DEFORMABLE_WORLD)
pybullet.setGravity(0, 0, -9.8)
self.cache_video = []
# # 创建坐标轴的长度
# axis_length = 1.0
#
# # 创建坐标轴的原点
# origin = [0, 0, 0]
#
# # 创建x轴
# pybullet.addUserDebugLine(origin, [axis_length, 0, 0], [1, 0, 0])
#
# # 创建y轴
# pybullet.addUserDebugLine(origin, [0, axis_length, 0], [0, 1, 0])
#
# # 创建z轴
# pybullet.addUserDebugLine(origin, [0, 0, axis_length], [0, 0, 1])
#
# # 创建轴标签
# pybullet.addUserDebugText('X', [axis_length, 0, 0], textColorRGB=[1, 0, 0])
# pybullet.addUserDebugText('Y', [0, axis_length, 0], textColorRGB=[0, 1, 0])
# pybullet.addUserDebugText('Z', [0, 0, axis_length], textColorRGB=[0, 0, 1])
# Temporarily disable rendering to load URDFs faster.
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 0)
# Add robot.
pybullet.loadURDF("plane.urdf", [0, 0, -0.001])
if self.use_ur5:
self.robot_id = pybullet.loadURDF("ur5e/ur5e.urdf", [0, -0.5, 0],
flags=pybullet.URDF_USE_MATERIAL_COLORS_FROM_MTL)
self.ghost_id = pybullet.loadURDF("ur5e/ur5e.urdf", [0, 0, -10]) # For forward kinematics.
self.joint_ids = [pybullet.getJointInfo(self.robot_id, i) for i in
range(pybullet.getNumJoints(self.robot_id))]
self.joint_ids = [j[0] for j in self.joint_ids if j[2] == pybullet.JOINT_REVOLUTE]
else:
self.robot_id = pybullet.loadURDF("franka_description/robots/franka_panda.urdf", [0, 0, 0],
flags=pybullet.URDF_USE_MATERIAL_COLORS_FROM_MTL)
self.ghost_id = pybullet.loadURDF("franka_description/robots/franka_panda.urdf",
[0, 0, -10]) # For forward kinematics.
self.joint_ids = [pybullet.getJointInfo(self.robot_id, i) for i in
range(pybullet.getNumJoints(self.robot_id))]
self.joint_ids = [j[0] for j in self.joint_ids if j[2] == pybullet.JOINT_REVOLUTE]
self.pybullet_id_dict['robot'] = self.robot_id
self.pybullet_id_dict['ghost'] = self.ghost_id
# Move robot to home configuration.
for i in range(len(self.joint_ids)):
pybullet.resetJointState(self.robot_id, self.joint_ids[i], self.home_joints[i])
if self.use_ur5:
# Add gripper.
if self.gripper is not None:
while self.gripper.constraints_thread.is_alive():
self.constraints_thread_active = False
self.gripper = Robotiq2F85(self.robot_id, self.ee_link_id)
self.pybullet_id_dict['gripper'] = self.gripper.body
self.gripper.release()
# self.gripper.list_joint_names()
# ee_to_tip transformation
ee_state = pybullet.getLinkState(self.robot_id, self.ee_link_id)
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_rot_mat = pybullet.getMatrixFromQuaternion(tip_state[1])
ee_rot_mat = pybullet.getMatrixFromQuaternion(ee_state[1])
tip_transform_mat = np.eye(4)
ee_transform_mat = np.eye(4)
tip_transform_mat[:3, :3] = np.reshape(tip_rot_mat, (3, 3))
ee_transform_mat[:3, :3] = np.reshape(ee_rot_mat, (3, 3))
tip_transform_mat[:3, 3] = tip_state[0]
ee_transform_mat[:3, 3] = ee_state[0]
self.ee_to_tip = np.dot(np.linalg.inv(tip_transform_mat), ee_transform_mat)
# Load objects according to config.
place_info, pick_info = self.pick_place_info[id][0], self.pick_place_info[id][1]
print(f'now processing {pick_info}')
with open(pick_info) as f:
self.source_info = json.load(f)
with open(place_info) as f:
self.target_info = json.load(f)
self.cam_info = self.source_info['camera_data']
z_support_max = 0
for source in self.source_info['objects']:
class_name = source['class']
object_name = source['name']
if class_name != 'support_table':
urdf_path = os.path.join(self.model_base, class_name, object_name + '.urdf')
else:
urdf_path = os.path.join(self.model_base, class_name, object_name.split('_')[0] + '.urdf')
support_mesh = trimesh.load(urdf_path.replace('.urdf', '.obj')).apply_scale(source['scale'])
z_support_max = support_mesh.bounds[1][2]
self.table_height = z_support_max
object_name = 'support_table'
# obj = trimesh.load(urdf_path.replace('.urdf','.obj')).apply_scale(info['scale'])
ini_pose = np.array(source['local_to_world_matrix']).reshape(4, 4).T
ini_bbox = np.array(source['param6'])
# normalize scale sR /= s s = Frobenius
rot_F = np.linalg.norm(ini_pose[:3, :3], ord='fro')
ini_pose[:3, :3] /= (rot_F / np.sqrt(3))
# obj_list.append(obj.copy().apply_transform(pose))
object_position = ini_pose[:3, 3]
object_orieation = trans.quaternion_from_matrix(ini_pose)
object_id = pybullet.loadURDF(urdf_path, object_position, object_orieation)
self.pybullet_id_dict[object_name] = object_id
self.ini_pose_dict[object_name] = ini_pose
self.ini_bbox_dict[object_name] = ini_bbox
# do target pose statistics. TODO This is not the final version. Only for the transformation test. Target poses should be calculated by ICP or sth similar.
target_pose = None
target_bbox = None
for target in self.target_info['objects']:
if target['name'] == object_name:
target_pose = np.array(target['local_to_world_matrix']).reshape(4, 4).T
target_bbox = np.array(target['param6'])
# normalize scale sR /= s s = Frobenius
rot_target = np.linalg.norm(target_pose[:3, :3], ord='fro')
target_pose[:3, :3] /= (rot_target / np.sqrt(3))
break
self.target_pose_dict[object_name] = target_pose
self.target_bbox_dict[object_name] = target_bbox
# rel_pose = None
# for target in target_info['objects']:
# if target['name'] == object_name:
# target_pose = np.array(target['local_to_world_matrix']).reshape(4,4).T
# # normalize scale sR /= s s = Frobenius
# rot_target = np.linalg.norm(target_pose[:3, :3], ord='fro')
# target_pose[:3, :3] /= (rot_target / np.sqrt(3))
# rel_pose = np.matmul(target_pose, np.linalg.inv(ini_pose))
# break
# self.rel_pose_dict[object_name] = rel_pose
# TODO adjust mass
pybullet.changeDynamics(object_id, -1, mass=0)
# pybullet.changeDynamics(object_id, -1, mass=0.2, restitution=0.5)
# if class_name == 'knife' or class_name == 'fork' or class_name == 'tablespoon' or class_name == 'teaspoon':
# pybullet.changeDynamics(object_id, -1, mass=0.1, restitution=0.5)
if class_name == 'support_table':
position, _ = pybullet.getBasePositionAndOrientation(object_id)
pybullet.changeDynamics(object_id, -1, mass=0)
# pybullet.createConstraint(
# parentBodyUniqueId=object_id,
# parentLinkIndex=-1, # 表示物体的基础部分
# childBodyUniqueId=-1, # 表示世界坐标系
# childLinkIndex=-1,
# jointType=pybullet.JOINT_FIXED, # 表示这是一个固定的约束
# jointAxis=(0, 0, 0),
# parentFramePosition=position,
# childFramePosition=(0, 0, 0)
# )
# trimesh.scene.Scene(obj_list).show()
# Reset the robot position to a higher place
position_robot, _ = pybullet.getBasePositionAndOrientation(self.robot_id)
position_robot = np.array(position_robot) + np.array([0, 0, self.table_height])
pybullet.resetBasePositionAndOrientation(self.robot_id, position_robot,
pybullet.getQuaternionFromEuler([0, 0, -180]))
# Move robot to home configuration.
for i in range(len(self.joint_ids)):
pybullet.resetJointState(self.robot_id, self.joint_ids[i], self.home_joints[i])
# Re-enable rendering.
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 1)
for _ in range(1000):
pybullet.stepSimulation()
time.sleep(1. / 240.)
return
def check_limit(self):
for joint_id in self.joint_ids:
joint_info = pybullet.getJointInfo(self.robot_id, joint_id)
joint_lower_limit = joint_info[8] # 最小限位
joint_upper_limit = joint_info[9] # 最大限位
joint_state = pybullet.getJointState(self.robot_id, joint_id)
joint_position = joint_state[0]
if joint_position < joint_lower_limit or joint_position > joint_upper_limit:
print(f'Joint {joint_id} of the robot is out of limits')
# # Move robot to home configuration.
# for i in range(len(self.joint_ids)):
# pybullet.setJointMotorControl2(self.robot_id, self.joint_ids[i], pybullet.POSITION_CONTROL,
# targetPosition=self.home_joints[i])
# for _ in range(720):
# self.step_sim_and_render()
return True
return False
def servoj(self, joints, gain=0.01):
"""Move to target joint positions with position control."""
pybullet.setJointMotorControlArray(
bodyIndex=self.robot_id,
jointIndices=self.joint_ids,
controlMode=pybullet.POSITION_CONTROL,
targetPositions=joints,
positionGains=[gain] * 6)
def movep(self, position, gain=0.01):
"""Move to target end effector position."""
joints = pybullet.calculateInverseKinematics(
bodyUniqueId=self.robot_id,
endEffectorLinkIndex=self.tip_link_id,
targetPosition=position,
targetOrientation=pybullet.getQuaternionFromEuler(self.home_ee_euler),
maxNumIterations=100)
self.servoj(joints, gain)
def move_matrix(self, matrix, gain=0.01):
"""Move to target end effector position."""
position, orientation_q = matrix[:3, 3], trans.quaternion_from_matrix(matrix)
joints = pybullet.calculateInverseKinematics(
bodyUniqueId=self.robot_id,
endEffectorLinkIndex=self.tip_link_id,
targetPosition=position,
targetOrientation=orientation_q,
maxNumIterations=100)
self.servoj(joints, gain)
def move_pos_ori(self, position, orientation_q, gain=0.01):
"""Move to target end effector position."""
joints = pybullet.calculateInverseKinematics(
bodyUniqueId=self.robot_id,
endEffectorLinkIndex=self.tip_link_id,
targetPosition=position,
targetOrientation=orientation_q,
maxNumIterations=100)
self.servoj(joints, gain)
def check_obj_gripper(self, gripper_id):
object_in_gripper = pybullet.getContactPoints(bodyA=gripper_id)
if not object_in_gripper:
description = "I guess the object is not in my gripper, returning.."
print(description)
self.description_list.append(description)
return object_in_gripper
def pick_step(self, grasps_w, opening, score, ee_to_tip):
"""Do pick and place motion primitive."""
done = False
best_grasp_w, best_opening = self.maximize_score_and_z_alignment(grasps_w, score, opening,
target_z=np.array([0, 0, -1]), score_weight=1,
alignment_weight=0)
grasp_tip = np.matmul(best_grasp_w, np.linalg.inv(ee_to_tip))
# # change gravity
# pybullet.changeDynamics(obj_id, -1, mass=0.1)
# climb to the higher space
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz = np.float32(tip_state[0])
hover_xyz_start = tip_xyz + np.float32([0, 0, 0.2])
hover_xyz_lift = grasp_tip[:3, 3] + np.float32([0, 0, 0.2])
dist_p = 100
while dist_p > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz = np.float32(tip_state[0])
dist_p = np.linalg.norm(hover_xyz_start - tip_xyz)
self.movep(hover_xyz_start)
self.step_sim_and_render()
# Move close to object.
dist_p, dist_r = 100, 100
close_pos = grasp_tip[:3, 3] - grasp_tip[:3, 2] * 0.03
close_ori = trans.quaternion_from_matrix(grasp_tip)
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(close_pos - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(close_ori, tip_rot)))
self.move_pos_ori(close_pos, close_ori)
self.step_sim_and_render()
# Move to object.
dist_p, dist_r = 100, 100
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(grasp_tip[:3, 3] - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(trans.quaternion_from_matrix(grasp_tip), tip_rot)))
self.move_matrix(grasp_tip, gain=0.005)
self.step_sim_and_render()
# Pick up object.
force_threshold = 500
t = 0
while t < 2400:
# right follower
right_finger_info = pybullet.getJointState(bodyUniqueId=self.gripper.body,
jointIndex=self.gripper.joint_name_dict[
'robotiq_2f_85_right_follower_joint'])
right_reaction_force = np.linalg.norm(right_finger_info[2][:3]) # right finger force
left_finger_info = pybullet.getJointState(bodyUniqueId=self.gripper.body,
jointIndex=self.gripper.joint_name_dict[
'robotiq_2f_85_left_follower_joint'])
left_reaction_force = np.linalg.norm(left_finger_info[2][:3]) # left finger force
# print(f'the force on the left finger is {left_reaction_force}, the force on the right finger is {right_reaction_force}')
# if abs(right_reaction_force) > force_threshold and abs(left_reaction_force) > force_threshold:
# self.gripper.stop() # Stop closing the gripper
# break
# else:
self.gripper.activate()
t += 1
self.step_sim_and_render()
# climb up with the object.
dist_p = 100
while dist_p > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz = np.float32(tip_state[0])
dist_p = np.linalg.norm(hover_xyz_lift - tip_xyz)
self.movep(hover_xyz_lift, 0.005)
self.step_sim_and_render()
# Move to a temporary location.
dist_p = 100
tem_loc = np.array([0.5, 0.5, 0.5])
while dist_p > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz = np.float32(tip_state[0])
dist_p = np.linalg.norm(tem_loc - tip_xyz)
self.movep(tem_loc, 0.001)
self.step_sim_and_render()
# drop the object
self.gripper.release()
for _ in range(720):
self.step_sim_and_render()
# Move robot to home configuration.
for i in range(len(self.joint_ids)):
pybullet.setJointMotorControl2(self.robot_id, self.joint_ids[i], pybullet.POSITION_CONTROL,
targetPosition=self.home_joints[i])
for _ in range(720):
self.step_sim_and_render()
# observation = self.get_observation()
# reward = self.get_reward()
done = True
info = {}
debug_clip = ImageSequenceClip(self.cache_video, fps=25)
return done
def rearrange_step(self, grasps_w, opening, score, ee_to_tip, weight=[0.5, 0.5], rel_pose=None, post=False):
"""Do pick and place motion primitive."""
done = False
best_grasp_w, best_opening = self.maximize_score_and_z_alignment(grasps_w, score, opening,
target_z=np.array([0, 0, -1]),
score_weight=weight[0], alignment_weight=weight[1],
rel_pose=rel_pose, post=post)
grasp_tip = np.matmul(best_grasp_w, np.linalg.inv(ee_to_tip))
place_pos = np.array([0.5, -0.4, grasp_tip[2, 3] + 0.2])
place_ori = trans.quaternion_from_matrix(grasp_tip)
# rel_pose is None means it is needed to be thrown away
if rel_pose is not None:
target = np.matmul(rel_pose, grasp_tip)
target_ori = trans.quaternion_from_matrix(target)
target_pos = target[:3, 3]
place_pos = np.array([target_pos[0], target_pos[1], target_pos[2] + 0.2])
place_ori = target_ori
# # climb to the higher space
# tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
# tip_xyz = np.float32(tip_state[0])
# hover_xyz_start = tip_xyz + np.float32([0, 0, 0.2])
# dist_p = 100
# while dist_p > 0.01:
# if self.check_limit():
# return done
# tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
# tip_xyz = np.float32(tip_state[0])
# dist_p = np.linalg.norm(hover_xyz_start - tip_xyz)
# self.movep(hover_xyz_start)
# self.step_sim_and_render()
# Move close to object.
dist_p, dist_r = 100, 100
close_pos = grasp_tip[:3, 3] - grasp_tip[:3, 2] * 0.03
close_ori = trans.quaternion_from_matrix(grasp_tip)
t = 0
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(close_pos - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(close_ori, tip_rot)))
self.move_pos_ori(close_pos, close_ori)
self.step_sim_and_render()
t += 1
if t > 10000:
description = "cant reach the obj"
self.description_list.append(description)
print(description)
return done
# Move to object.
dist_p, dist_r = 100, 100
t = 0
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(grasp_tip[:3, 3] - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(trans.quaternion_from_matrix(grasp_tip), tip_rot)))
self.move_matrix(grasp_tip)
self.step_sim_and_render()
t += 1
if t > 10000:
description = "cant move to the obj"
self.description_list.append(description)
print(description)
return done
# Pick up object.
force_threshold = 500
t = 0
while t < 2400:
# right follower
right_finger_info = pybullet.getJointState(bodyUniqueId=self.gripper.body,
jointIndex=self.gripper.joint_name_dict[
'robotiq_2f_85_right_follower_joint'])
right_reaction_force = np.linalg.norm(right_finger_info[2][:3]) # right finger force
left_finger_info = pybullet.getJointState(bodyUniqueId=self.gripper.body,
jointIndex=self.gripper.joint_name_dict[
'robotiq_2f_85_left_follower_joint'])
left_reaction_force = np.linalg.norm(left_finger_info[2][:3]) # left finger force
# print(f'the force on the left finger is {left_reaction_force}, the force on the right finger is {right_reaction_force}')
# if abs(right_reaction_force) > force_threshold and abs(left_reaction_force) > force_threshold:
# self.gripper.stop() # Stop closing the gripper
# break
# else:
# TODO adjust this function
self.gripper.check_finger_force()
self.gripper.activate()
t += 1
self.step_sim_and_render()
# climb up with the object with the same gesture.
hover_xyz_lift = grasp_tip[:, 3] + np.float32([0, 0, 0.2, 0])
hover_lift_m = np.concatenate((grasp_tip[:, 0:3], hover_xyz_lift.reshape(4, -1)), axis=1)
dist_p, dist_r = 100, 100
t = 0
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit() or not self.check_obj_gripper(self.gripper.body):
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(hover_xyz_lift[:3] - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(trans.quaternion_from_matrix(hover_lift_m), tip_rot)))
self.gripper.activate()
self.move_matrix(hover_lift_m, 0.005)
self.step_sim_and_render()
self.gripper.check_finger_force()
t += 1
if t > 10000:
print("cant climb up")
# Move to the target location using the targeted ori gesture.
dist_p, dist_r = 100, 100
t = 0
unreach_flag = 0
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit() or not self.check_obj_gripper(self.gripper.body):
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(place_pos - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(place_ori, tip_rot)))
self.move_pos_ori(place_pos, place_ori, 0.001)
self.step_sim_and_render()
self.gripper.check_finger_force()
t += 1
if t > 10000:
description = "can't move to the target location using the targeted ori gesture. I will drop it"
self.description_list.append(description)
print(description)
unreach_flag = 1
break
# low down the object
lowdown_xyz = place_pos - np.float32([0, 0, 0.17])
dist_p, dist_r = 100, 100
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit() or not self.check_obj_gripper(self.gripper.body):
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(lowdown_xyz - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(place_ori, tip_rot)))
self.move_pos_ori(lowdown_xyz, place_ori, 0.005)
self.step_sim_and_render()
self.gripper.check_finger_force()
# release the gripper
self.gripper.release()
for _ in range(720):
self.step_sim_and_render()
# let the gripper retreat 3cm
ori_matrix = trans.quaternion_matrix(place_ori)
retreat_pos = lowdown_xyz - np.array(ori_matrix[:3, 2]) * 0.03
dist_p, dist_r = 100, 100
while dist_p > 0.01 or dist_r > 0.01:
if self.check_limit():
return done
tip_state = pybullet.getLinkState(self.robot_id, self.tip_link_id)
tip_xyz, tip_rot = np.float32(tip_state[0]), np.float32(tip_state[1])
dist_p = np.linalg.norm(retreat_pos - tip_xyz)
dist_r = 2 * np.arccos(abs(np.dot(place_ori, tip_rot)))
self.move_pos_ori(retreat_pos, place_ori, 0.005)
self.step_sim_and_render()
observation = self.get_observation()
reward = self.get_reward()
done = True if not unreach_flag else False
info = {}
return done
def step(self, action=None):
"""Do pick and place motion primitive."""
pick_xyz, place_xyz = action["pick"].copy(), action["place"].copy()
# Set fixed primitive z-heights.
hover_xyz = pick_xyz.copy() + np.float32([0, 0, 0.2])
pick_xyz[2] = 0.03
place_xyz[2] = 0.15
# Move to object.
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
while np.linalg.norm(hover_xyz - ee_xyz) > 0.01:
self.movep(hover_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
while np.linalg.norm(pick_xyz - ee_xyz) > 0.01:
self.movep(pick_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
# Pick up object.
self.gripper.activate()
for _ in range(240):
self.step_sim_and_render()
while np.linalg.norm(hover_xyz - ee_xyz) > 0.01:
self.movep(hover_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
# Move to place location.
while np.linalg.norm(place_xyz - ee_xyz) > 0.01:
self.movep(place_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
# Place down object.
while (not self.gripper.detect_contact()) and (place_xyz[2] > 0.03):
place_xyz[2] -= 0.001
self.movep(place_xyz)
for _ in range(3):
self.step_sim_and_render()
self.gripper.release()
for _ in range(240):
self.step_sim_and_render()
place_xyz[2] = 0.2
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
while np.linalg.norm(place_xyz - ee_xyz) > 0.01:
self.movep(place_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
place_xyz = np.float32([0, -0.5, 0.2])
while np.linalg.norm(place_xyz - ee_xyz) > 0.01:
self.movep(place_xyz)
self.step_sim_and_render()
ee_xyz = np.float32(pybullet.getLinkState(self.robot_id, self.tip_link_id)[0])
observation = self.get_observation()
reward = self.get_reward()
done = False
info = {}
return observation, reward, done, info
def set_alpha_transparency(self, alpha: float) -> None:
for id in range(20):
visual_shape_data = pybullet.getVisualShapeData(id)
for i in range(len(visual_shape_data)):
object_id, link_index, _, _, _, _, _, rgba_color = visual_shape_data[i]
rgba_color = list(rgba_color[0:3]) + [alpha]
pybullet.changeVisualShape(
self.robot_id, linkIndex=i, rgbaColor=rgba_color)
pybullet.changeVisualShape(
self.gripper.body, linkIndex=i, rgbaColor=rgba_color)
def step_sim_and_render(self):
pybullet.stepSimulation()
self.sim_step += 1
# Render current image at 8 FPS.
if self.sim_step % 60 == 0:
self.cache_video.append(self.image_for_video(self.cam_info))
def image_for_video(self, cam_info):
cam_info_video = copy.deepcopy(cam_info)
cam_info_video['height'] = 720
cam_info_video['width'] = 1280
# Camera parameters.
intrinsics = (cam_info_video['width']/2, 0, cam_info_video['width']/2, 0, cam_info_video['height']/2, cam_info_video['height']/2, 0, 0, 1)
noise = True
# OpenGL camera settings.
focal_len = intrinsics[0]
znear, zfar = (0.01, 10.)
# change z and y
cam_info_video['camera_look_at']['up'] = [cam_info_video['camera_look_at']['up'][0], cam_info_video['camera_look_at']['up'][1], -cam_info_video['camera_look_at']['up'][2]]
render_eye = (cam_info_video['camera_look_at']['eye'][0], -cam_info_video['camera_look_at']['eye'][1]+0.2, cam_info_video['camera_look_at']['eye'][2])
viewm = pybullet.computeViewMatrix(render_eye,
tuple(cam_info_video['camera_look_at']['at']),
tuple(cam_info_video['camera_look_at']['up']))
fovh = (cam_info_video['height'] / 2) / focal_len
fovh = 180 * np.arctan(fovh) * 2 / np.pi
# Notes: 1) FOV is vertical FOV 2) aspect must be float
aspect_ratio = cam_info_video['width'] / cam_info_video['height']
projm = pybullet.computeProjectionMatrixFOV(fovh, aspect_ratio, znear, zfar)
# Render with OpenGL camera settings.
_, _, color, _, _ = pybullet.getCameraImage(
width=cam_info_video['width'],
height=cam_info_video['height'],
viewMatrix=viewm,
projectionMatrix=projm,
shadow=1,
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
# Get color image.
color_image_size = (cam_info_video['height'], cam_info_video['width'], 4)
color = np.array(color, dtype=np.uint8).reshape(color_image_size)
color = color[::-1, ::-1, :3] # remove alpha channel
if noise:
color = np.int32(color)
color += np.int32(np.random.normal(0, 3, color.shape))
color = np.uint8(np.clip(color, 0, 255))