-
Notifications
You must be signed in to change notification settings - Fork 28
/
old_robot.py
executable file
·2490 lines (2117 loc) · 135 KB
/
old_robot.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 socket
import select
import struct
import time
import os
import numpy as np
import itertools
import utils
import traceback
import copy
from simulation import vrep
from scipy import ndimage, misc
from glob import glob
try:
from gripper.robotiq_2f_gripper_ctrl import RobotiqCGripper
except ImportError:
print('Real robotiq gripper control is not available. '
'Ensure pymodbus is installed:\n'
' pip3 install --user --upgrade pymodbus\n')
RobotiqCGripper = None
def gripper_control_pose_to_arm_control_pose(gripper_translation, gripper_orientation, gripper_to_arm_transform=None):
# arm_trans = np.eye(4,4)
# arm_trans[0:3,3] = np.asarray(gripper_translation)
# # gripper_orientation = [-gripper_orientation[0], -gripper_orientation[1], -gripper_orientation[2]]
# arm_rotm = np.eye(4,4)
# arm_rotm[0:3,0:3] = np.linalg.inv(utils.euler2rotm(gripper_orientation))
# gripper_pose = np.dot(arm_trans, arm_rotm) # Compute rigid transformation representating camera pose
if gripper_to_arm_transform is None:
return gripper_translation, gripper_orientation
gripper_pose = utils.axis_angle_and_translation_to_rigid_transformation(gripper_translation, gripper_orientation)
# print('gripper_control_pose_to_arm_control_pose() gripper_pose: \n' + str(gripper_pose))
# 4x4 transform of the arm pose
arm_pose = np.dot(gripper_pose, utils.pose_inv(gripper_to_arm_transform))
# arm_pose = np.dot(gripper_pose, gripper_to_arm_transform)
# arm_pose = np.dot(utils.pose_inv(gripper_to_arm_transform), gripper_pose)
# arm_pose = np.dot(gripper_to_arm_transform, gripper_pose)
arm_orientation_axis_angle = utils.rotm2angle(arm_pose[0:3,0:3])
arm_orientation = arm_orientation_axis_angle[0]*np.asarray(arm_orientation_axis_angle[1:4])
arm_translation = arm_pose[0:3,3]
return arm_translation, arm_orientation
def orientation_and_angle_to_push_direction(heightmap_rotation_angle, push_orientation=None):
if push_orientation is None:
push_orientation = [1.0, 0.0]
# Compute push direction and endpoint (push to right of rotated heightmap)
push_direction = np.asarray([push_orientation[0]*np.cos(heightmap_rotation_angle) - push_orientation[1]*np.sin(heightmap_rotation_angle), push_orientation[0]*np.sin(heightmap_rotation_angle) + push_orientation[1]*np.cos(heightmap_rotation_angle), 0.0])
return push_direction
def push_poses(heightmap_rotation_angle, position, workspace_limits, push_orientation=None, push_length=0.1, up_length=0.2, tilt_axis=None, gripper_to_arm_transform=None, buffer=0.005):
"""
# Returns
position, up_pos, push_endpoint, push_direction, tool_orientation_rotm
"""
if push_orientation is None:
push_orientation = [1.0, 0.0]
if tilt_axis is None:
tilt_axis = np.asarray([0,0,np.pi/2])
# Compute push direction and endpoint (push to right of rotated heightmap)
# Compute target location (push to the right)
push_direction = np.asarray([push_orientation[0]*np.cos(heightmap_rotation_angle) - push_orientation[1]*np.sin(heightmap_rotation_angle), push_orientation[0]*np.sin(heightmap_rotation_angle) + push_orientation[1]*np.cos(heightmap_rotation_angle), 0.0])
target_x = min(max(position[0] + push_direction[0]*push_length, workspace_limits[0][0]), workspace_limits[0][1])
target_y = min(max(position[1] + push_direction[1]*push_length, workspace_limits[1][0]), workspace_limits[1][1])
push_endpoint = np.asarray([target_x, target_y, position[2] + buffer])
push_direction.shape = (3, 1)
# Compute tool orientation from heightmap rotation angle
# TODO(ahundt) tool_rotation_angle, particularly dividing by 2, may affect (1) sim to real transfer, and (2) common sense checks, especially considering that our real robot gripper is not centered on the tool control point. Verify transforms!
tool_rotation_angle = heightmap_rotation_angle/2
# tool_orientation = orientation_and_angle_to_push_direction(tool_rotation_angle, push_orientation)*np.pi
tool_orientation = np.asarray([push_orientation[0]*np.cos(tool_rotation_angle) - push_orientation[1]*np.sin(tool_rotation_angle), push_orientation[0]*np.sin(tool_rotation_angle) + push_orientation[1]*np.cos(tool_rotation_angle), 0.0])*np.pi
tool_orientation_angle = np.linalg.norm(tool_orientation)
tool_orientation_axis = tool_orientation/tool_orientation_angle
tool_orientation_rotm = utils.angle2rotm(tool_orientation_angle, tool_orientation_axis, point=None)[:3,:3]
# Compute tilted tool orientation during push
tilt_axis = np.dot(utils.euler2rotm(tilt_axis)[:3,:3], push_direction)
tilt_rotm = utils.angle2rotm(-np.pi/8, tilt_axis, point=None)[:3,:3]
tilted_tool_orientation_rotm = np.dot(tilt_rotm, tool_orientation_rotm)
tilted_tool_orientation_axis_angle = utils.rotm2angle(tilted_tool_orientation_rotm)
tilted_tool_orientation = tilted_tool_orientation_axis_angle[0]*np.asarray(tilted_tool_orientation_axis_angle[1:4])
# Push only within workspace limits
position = np.asarray(position).copy()
position[0] = min(max(position[0], workspace_limits[0][0]), workspace_limits[0][1])
position[1] = min(max(position[1], workspace_limits[1][0]), workspace_limits[1][1])
position[2] = max(position[2] + buffer, workspace_limits[2][0] + buffer) # Add buffer to surface
up_pos = np.array([position[0],position[1],position[2] + up_length])
# convert to real arm tool control points, rather than heightmap based control points
position, tool_orientation = gripper_control_pose_to_arm_control_pose(position, tool_orientation, gripper_to_arm_transform)
up_pos, _ = gripper_control_pose_to_arm_control_pose(up_pos, tool_orientation, gripper_to_arm_transform)
push_endpoint, tilted_tool_orientation = gripper_control_pose_to_arm_control_pose(push_endpoint, tilted_tool_orientation, gripper_to_arm_transform)
return position, up_pos, push_endpoint, push_direction, tool_orientation, tilted_tool_orientation
class Robot(object):
"""
Key member variables:
self.color_space: list of colors to give objects
self.color_names: list of strings identifying colors in color_space
self.stored_action_labels: name of actions for stacking one hot encoding, set if self.grasp_color_task = True.
self.object_handles: list of vrep object handles, the unique identifier integer indices needed for controlling objects in the vrep simulator
self.workspace_limits: bounds of the valid object workspace.
"""
def __init__(self, is_sim=True, obj_mesh_dir=None, num_obj=None, workspace_limits=None,
tcp_host_ip='192.168.1.155', tcp_port=502, rtc_host_ip=None, rtc_port=None,
is_testing=False, test_preset_cases=None, test_preset_file=None, test_preset_arr=None,
place=False, grasp_color_task=False, real_gripper_ip='192.168.1.11', calibrate=False,
unstack=False, heightmap_resolution=0.002, randomized=True, obj_scale=1,
task_type=None):
'''
real_gripper_ip: None to assume the gripper is connected via the UR5,
specify an ip address to directly use TCPModbus to talk directly with the gripper.
Default is 192.168.1.11.
'''
self.is_sim = is_sim
if workspace_limits is None:
# workspace_limits = np.asarray([[0.3, 0.748], [-0.224, 0.224], [-0.255, -0.1]]) # Cols: min max, Rows: x y z (define workspace limits in robot coordinates)
if is_sim:
workspace_limits = np.asarray([[-0.724, -0.276], [-0.224, 0.224], [-0.0001, 0.5]]) # Cols: min max, Rows: x y z (define workspace limits in robot coordinates)
else:
# Corner near window on robot base side
# [0.47984089 0.34192974 0.02173636]
# Corner on the side of the cameras and far from the window
# [ 0.73409861 -0.45199446 -0.00229499]
# Dimensions of workspace should be 448 mm x 448 mm. That's 224x224 pixels with each pixel being 2mm x2mm.
workspace_limits = np.asarray([[0.376, 0.824], [-0.264, 0.184], [-0.07, 0.4]]) # Cols: min max, Rows: x y z (define workspace limits in robot coordinates)
self.workspace_limits = workspace_limits
self.heightmap_resolution = heightmap_resolution
self.place_task = place
self.unstack = unstack
self.place_pose_history_limit = 6
self.grasp_color_task = grasp_color_task
self.sim_home_position = [-0.3, 0.0, 0.45] # old value [-0.3, 0, 0.3]
# self.gripper_ee_offset = 0.17
# self.gripper_ee_offset = 0.15
self.background_heightmap = None
self.tool_tip_to_gripper_center_transform = None
# list of place position attempts
self.place_pose_history = []
# HK: If grasping specific block color...
#
# TODO: Change to random color not just red block using (b = [0, 1, 2, 3] np.random.shuffle(b)))
# after grasping, put the block back
if grasp_color_task:
self.color_names = ['blue', 'green', 'yellow', 'red']
else:
self.color_names = ['blue', 'green', 'yellow', 'red', 'brown', 'orange', 'gray', 'purple', 'cyan', 'pink']
# task type (defaults to None)
self.task_type = task_type
# If in simulation...
if self.is_sim:
# Tool pose tolerance for blocking calls, [x, y, z, roll, pitch, yaw]
# with units [m, m, m, rad, rad, rad]
# TODO(ahundt) double check rad rad rad, it might be axis/angle where magnitude is rotation length.
self.tool_pose_tolerance = [0.001,0.001,0.001,0.01,0.01,0.01]
self.push_vertical_offset = 0.026
if num_obj is None:
num_obj = 10
if obj_mesh_dir is None:
obj_mesh_dir = os.path.abspath('objects/toys')
# Define colors for object meshes (Tableau palette)
# self.color_space = np.asarray([[78.0, 121.0, 167.0], # blue
# [89.0, 161.0, 79.0], # green
# [156, 117, 95], # brown
# [242, 142, 43], # orange
# [237.0, 201.0, 72.0], # yellow
# [186, 176, 172], # gray
# [255.0, 87.0, 89.0], # red
# [176, 122, 161], # purple
# [118, 183, 178], # cyan
# [255, 157, 167]])/255.0 #pink
if grasp_color_task:
self.color_space = np.asarray([[78.0, 121.0, 167.0], # blue
[89.0, 161.0, 79.0], # green
[237.0, 201.0, 72.0], # yellow
[255.0, 87.0, 89.0]])/255.0 # red
else:
self.color_space = np.asarray([[78.0, 121.0, 167.0], # blue
[89.0, 161.0, 79.0], # green
[237.0, 201.0, 72.0], # yellow
[255.0, 87.0, 89.0], # red
[156, 117, 95], # brown
[242, 142, 43], # orange
[186, 176, 172], # gray
[176, 122, 161], # purple
[118, 183, 178], # cyan
[255, 157, 167]])/255.0 #pink
# Read files in object mesh directory
self.obj_mesh_dir = obj_mesh_dir
self.num_obj = num_obj
# TODO(HK) specify which objects to load here from a command line parameter, should be able ot load one repeatedly
#self.mesh_list = os.listdir(self.obj_mesh_dir)
# Restrict only the .obj files
self.mesh_list = sorted(glob(os.path.join(self.obj_mesh_dir, "*.obj")))
#print(f"self.meshlist: {self.mesh_list}")
# Randomly choose objects to add to scene
self.obj_mesh_ind = np.random.randint(0, len(self.mesh_list), size=self.num_obj)
self.obj_mesh_color = self.color_space[np.asarray(range(self.num_obj)) % self.color_space.shape[0], :]
# Make sure to have the server side running in V-REP:
# in a child script of a V-REP scene, add following command
# to be executed just once, at simulation start:
#
# simExtRemoteApiStart(19999)
#
# then start simulation, and run this program.
#
# IMPORTANT: for each successful call to simxStart, there
# should be a corresponding call to simxFinish at the end!
# MODIFY remoteApiConnections.txt
if tcp_port is None or tcp_port == 30002 or tcp_port == 502:
print("WARNING: default tcp port changed to 19997 for is_sim")
tcp_port = 19997
self.tcp_port = tcp_port
#print(f"bp 1")
self.restart_sim(connect=True)
# initialize some startup state values and handles for
# the joint configurations and home position
# sim_joint_handles are unique identifying integers to control the robot joints in the simulator
self.sim_joint_handles = []
# home_joint_config will contain the floating point joint angles representing the home configuration.
self.home_joint_config = []
self.go_home()
# set the home joint config based on the initialized simulation
self.home_joint_config = self.get_joint_position()
#print(f"got joints")
self.is_testing = is_testing
self.test_preset_cases = test_preset_cases
self.test_preset_file = test_preset_file
self.test_preset_arr = test_preset_arr
# Setup virtual camera in simulation
self.setup_sim_camera()
# Scaling used when importing objects
self.obj_scale = obj_scale
self.png_list = sorted(glob(os.path.join(self.obj_mesh_dir, "*.png")))
self.textured = True if len(self.png_list) > 0 else False
self.logoblock_dataset = self.textured
self.randomized = randomized
# If testing, read object meshes and poses from test case file
print(f"self.is_testing {is_testing} self.test_preset_cases {self.test_preset_cases}")
if self.is_testing and self.test_preset_cases:
print(f"loading preset case")
self.load_preset_case()
# Add objects to simulation environment
self.add_objects()
# If in real-settings...
else:
# Tool pose tolerance for blocking calls, [x, y, z, roll, pitch, yaw]
# with units [m, m, m, rad, rad, rad]
# TODO(ahundt) double check rad rad rad, it might be axis/angle where magnitude is rotation length.
self.tool_pose_tolerance = [0.002,0.002,0.002,0.01,0.01,0.01]
self.push_vertical_offset = 0.01
# Connect to robot client
self.tcp_host_ip = tcp_host_ip
self.tcp_port = tcp_port
# self.tcp_socket.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
# Connect as real-time client to parse state data
self.rtc_host_ip = rtc_host_ip
self.rtc_port = rtc_port
# Default home joint configuration
# self.home_joint_config = [-np.pi, -np.pi/2, np.pi/2, -np.pi/2, -np.pi/2, 0]
# self.home_joint_config = [-(180.0/360.0)*2*np.pi, -(84.2/360.0)*2*np.pi, (112.8/360.0)*2*np.pi, -(119.7/360.0)*2*np.pi, -(90.0/360.0)*2*np.pi, 0.0]
# Costar dataset home joint config
# self.home_joint_config = [-0.202, -0.980, -1.800, -0.278, 1.460, 1.613]
# Real Good Robot Home Joint Config (gripper low and near base)
self.home_joint_config = [-0.021765167640454663, -0.7721485323791424, -2.137509664960675, -1.8396634790764201, 1.5608016750418263, 1.7122485182908058]
self.home_cart = [0.16452807896085456, -0.1140799890027773, 0.3401360989767276, -0.25284986938091303, -3.0949552373620137, 0.018920323919325615]
self.home_cart_low = self.home_cart
# gripper high above scene and camera
# self.home_joint_config = [0.2, -1.62, -0.85, -2.22, 1.57, 1.71]
# self.home_cart = [0.4387869054651441, -0.022525365646335706, 0.6275609068446096, -0.09490323444344208, 3.1179780725241626, 0.004632836623511681]
# self.home_cart_low = [0.4387869054651441, -0.022525365646335706, 0.3275609068446096, -0.09490323444344208, 3.1179780725241626, 0.004632836623511681]
# Default joint speed configuration
self.joint_acc = 4.0 # Safe: 1.4 Fast: 8
self.joint_vel = 2.0 # Safe: 1.05 Fast: 3
# Joint tolerance for blocking calls
self.joint_tolerance = 0.01
# Default tool speed configuration
self.tool_acc = 1.0 # Safe: 0.5 Fast: 1.2
self.tool_vel = 0.5 # Safe: 0.2 Fast: 0.5
self.move_sleep = 1.0 # Safe: 2.0 Fast: 1.0
# Initialize the real gripper based on user configuration
if real_gripper_ip is None:
self.gripper = None
elif RobotiqCGripper is None:
# Install instructions have already printed (see the imports section)
# and we cannot run in this mode without pymodbus, so exit.
exit(1)
else:
self.gripper = RobotiqCGripper(real_gripper_ip)
self.gripper.wait_for_connection()
self.gripper.reset()
self.gripper.activate()
# Move robot to home pose
self.close_gripper()
self.go_home()
self.open_gripper()
# Fetch RGB-D data from RealSense camera
from real.camera import Camera
self.camera = Camera(calibrate=calibrate)
self.cam_intrinsics = self.camera.intrinsics
# Load camera pose (from running calibrate.py), intrinsics and depth scale
if not calibrate and os.path.isfile('real/robot_base_to_camera_pose.txt') and os.path.isfile('real/camera_depth_scale.txt'):
self.cam_pose = np.loadtxt('real/robot_base_to_camera_pose.txt', delimiter=' ')
self.cam_depth_scale = np.loadtxt('real/camera_depth_scale.txt', delimiter=' ')
else:
print('WARNING: Camera Calibration is not yet available, running calibrate_ros.py '
'will create the required files: real/robot_base_to_camera_pose.txt and real/camera_depth_scale.txt')
# Camera calibration
self.cam_pose = None
self.cam_depth_scale = None
# Get the transform to the gripper center, this is necessary when the robot control
# poses differs from where the gripper center is, so a transform applying a correction is needed.
if not calibrate and os.path.isfile('real/tool_tip_to_ar_tag_transform.txt'):
self.tool_tip_to_gripper_center_transform = np.loadtxt('real/tool_tip_to_ar_tag_transform.txt', delimiter=' ')
if os.path.isfile('real/background_heightmap.depth.png'):
import cv2
# load depth image saved in 1e-5 meter increments
# see logger.py save_heightmaps() and trainer.py load_sample()
# for the corresponding save and load functions
self.background_heightmap = np.array(cv2.imread('real/background_heightmap.depth.png', cv2.IMREAD_ANYDEPTH)).astype(np.float32) / 100000
# TODO(ahundt) HACK REMOVE background_heightmap subtraction, COLLECT HEIGHTMAP AGAIN, SEE README.md for instructions
# self.background_heightmap -= 0.03
# real robot must use unstacking
if self.place_task:
self.unstack = True
def load_preset_case(self, test_preset_file=None):
if test_preset_file is None:
#print(f"preset file is {self.test_preset_file}")
test_preset_file = self.test_preset_file
file = open(test_preset_file, 'r')
file_content = file.readlines()
self.test_obj_mesh_files = []
self.test_obj_mesh_colors = []
self.test_obj_positions = []
self.test_obj_orientations = []
for object_idx in range(self.num_obj):
file_content_curr_object = file_content[object_idx].split()
self.test_obj_mesh_files.append(os.path.join(self.obj_mesh_dir,file_content_curr_object[0]))
self.test_obj_mesh_colors.append([float(file_content_curr_object[1]),float(file_content_curr_object[2]),float(file_content_curr_object[3])])
self.test_obj_positions.append([float(file_content_curr_object[4]),float(file_content_curr_object[5]),float(file_content_curr_object[6])])
self.test_obj_orientations.append([float(file_content_curr_object[7]),float(file_content_curr_object[8]),float(file_content_curr_object[9])])
file.close()
self.obj_mesh_color = np.asarray(self.test_obj_mesh_colors)
def setup_sim_camera(self):
#print(f"getting camera data")
# Get handle to camera
sim_ret, self.cam_handle = vrep.simxGetObjectHandle(self.sim_client, 'Vision_sensor_persp', vrep.simx_opmode_blocking)
#print(f"camera bp 1")
# Get camera pose and intrinsics in simulation
sim_ret, cam_position = vrep.simxGetObjectPosition(self.sim_client, self.cam_handle, -1, vrep.simx_opmode_blocking)
sim_ret, cam_orientation = vrep.simxGetObjectOrientation(self.sim_client, self.cam_handle, -1, vrep.simx_opmode_blocking)
cam_trans = np.eye(4,4)
cam_trans[0:3,3] = np.asarray(cam_position)
cam_orientation = [-cam_orientation[0], -cam_orientation[1], -cam_orientation[2]]
#print(f"camera bp 2")
cam_rotm = np.eye(4,4)
cam_rotm[0:3,0:3] = np.linalg.inv(utils.euler2rotm(cam_orientation))
self.cam_pose = np.dot(cam_trans, cam_rotm) # Compute rigid transformation representating camera pose
self.cam_intrinsics = np.asarray([[618.62, 0, 320], [0, 618.62, 240], [0, 0, 1]])
self.cam_depth_scale = 1
#print(f"camera bp 3")
# Get background image
self.bg_color_img, self.bg_depth_img = self.get_camera_data()
self.bg_depth_img = self.bg_depth_img * self.cam_depth_scale
#print(f"camera bp 4")
def generate_random_object_pose(self):
drop_x = (self.workspace_limits[0][1] - self.workspace_limits[0][0] - 0.2) * np.random.random_sample() + self.workspace_limits[0][0] + 0.1
drop_y = (self.workspace_limits[1][1] - self.workspace_limits[1][0] - 0.2) * np.random.random_sample() + self.workspace_limits[1][0] + 0.1
object_position = [drop_x, drop_y, 0.15]
object_orientation = [2*np.pi*np.random.random_sample(), 2*np.pi*np.random.random_sample(), 2*np.pi*np.random.random_sample()]
return drop_x, drop_y, object_position, object_orientation
def reposition_object_randomly(self, object_handle):
""" randomly set a specific object's position and orientation on
"""
drop_x, drop_y, object_position, object_orientation = self.generate_random_object_pose()
# Drop object at random x,y location and random orientation in robot workspace
vrep.simxSetObjectPosition(self.sim_client, object_handle, -1, object_position, vrep.simx_opmode_blocking)
vrep.simxSetObjectOrientation(self.sim_client, object_handle, -1, object_orientation, vrep.simx_opmode_blocking)
return object_position, object_orientation
def reposition_object_at_list_index_randomly(self, list_index):
object_handle = self.object_handles[list_index]
self.reposition_object_randomly(object_handle)
def reposition_object_at_list_index_to_location(self, obj_pos, obj_ori, index):
""" Reposition the object to a specified position and orientation """
object_handle = self.object_handles[index]
# TODO(adit98) figure out significance of plane_handle, set to -1 for now
if self.task_type is not None and self.task_type == 'unstack':
plane_handle=-1
else:
success, plane_handle = vrep.simxGetObjectHandle(self.sim_client, "Plane", vrep.simx_opmode_blocking)
vrep.simxSetObjectPosition(self.sim_client, object_handle, plane_handle, obj_pos, vrep.simx_opmode_blocking)
vrep.simxSetObjectOrientation(self.sim_client, object_handle, plane_handle, obj_ori, vrep.simx_opmode_blocking)
def add_objects(self):
# Add each object to robot workspace at x,y location and orientation (random or pre-loaded)
# object_handles is the list of unique vrep object integer identifiers, and it is how you control objects with the vrep API.
# We need to keep track of the object names and the corresponding colors.
self.object_handles = []
self.vrep_names = []
self.object_colors = []
add_success = False
failure_count = 0
while not add_success:
if (failure_count > 10 and failure_count %3 == 2) or len(self.object_handles) > len(self.obj_mesh_ind):
# If the simulation is not currently running, attempt to recover by restarting the simulation
connect = False
if failure_count > 50:
connect=True
# try restarting the simulation, and if that doesn't work disonnect entirely then reconnect
self.restart_sim(connect=connect)
self.object_handles = []
self.vrep_names = []
self.object_colors = []
for object_idx in range(len(self.obj_mesh_ind)):
# if setup for capture, no need for randomization / scrambling of the blocks.
if not self.randomized:
curr_mesh_file = os.path.join(self.obj_mesh_dir, self.mesh_list[object_idx])
else:
curr_mesh_file = os.path.join(self.obj_mesh_dir, self.mesh_list[self.obj_mesh_ind[object_idx]])
if self.is_testing and self.test_preset_cases:
curr_mesh_file = self.test_obj_mesh_files[object_idx]
# TODO(ahundt) define more predictable object names for when the number of objects is beyond the number of colors
#print(f"Currently Trying to Import: {curr_mesh_file}")
curr_shape_name = 'shape_%02d' % object_idx
self.vrep_names.append(curr_shape_name)
drop_x, drop_y, object_position, object_orientation = self.generate_random_object_pose()
if self.is_testing and self.test_preset_cases:
object_position = [self.test_obj_positions[object_idx][0], self.test_obj_positions[object_idx][1], self.test_obj_positions[object_idx][2]]
object_orientation = [self.test_obj_orientations[object_idx][0], self.test_obj_orientations[object_idx][1], self.test_obj_orientations[object_idx][2]]
# Loading object position and orientations from an array
if self.test_preset_arr is not None:
object_position = self.test_preset_arr[object_idx][0]
object_orientation = self.test_preset_arr[object_idx][1]
# Set the colors in order
#print(f"setting color at idx {object_idx} to {self.obj_mesh_color[object_idx]}")
object_color = [self.obj_mesh_color[object_idx][0], self.obj_mesh_color[object_idx][1], self.obj_mesh_color[object_idx][2]]
# If there are more objects than total colors this line will break,
# applies mod to loop back to the first color.
object_color_name = self.color_names[object_idx % len(self.color_names)]
# add the color of this object to the list.
self.object_colors.append(object_color_name)
#print('Adding object: ' + curr_mesh_file + ' as ' + curr_shape_name)
do_break = False
ret_ints = []
ret_resp = 0
while len(ret_ints) == 0:
do_break = False
#print(f"obj pos {object_position}")
#print(f"obj ori {object_orientation}")
#print(f"obj col {object_color}")
#print(curr_mesh_file)
#print(curr_shape_name)
# TODO: ZH, We don't really need this, remove this if statement after testing
scale = [self.obj_scale]
# Adding the objects via Lua script. If we are dealing with texture, different call to script.
if self.textured:
ret_resp,ret_ints,ret_floats,ret_strings,ret_buffer = vrep.simxCallScriptFunction(self.sim_client, 'remoteApiCommandServer',vrep.sim_scripttype_childscript,'importShapeWTextureWScale',[0, 0, 255, 0], object_position + object_orientation + object_color + scale, [curr_mesh_file, curr_shape_name], bytearray(), vrep.simx_opmode_blocking)
else:
ret_resp,ret_ints,ret_floats,ret_strings,ret_buffer = vrep.simxCallScriptFunction(self.sim_client, 'remoteApiCommandServer',vrep.sim_scripttype_childscript,'importShapeWScale',[0, 0, 255, 0], object_position + object_orientation + object_color + scale, [curr_mesh_file, curr_shape_name], bytearray(), vrep.simx_opmode_blocking)
if ret_resp == 8:
print('Failed to add ' + curr_mesh_file + ' to simulation. Auto retry ' + str(failure_count))
failure_count += 1
if failure_count % 3 == 2:
# If a few failures happen in a row, do a simulation reset and try again
do_break = True
break
elif failure_count > 100:
print('Failed to add new objects to simulation. Quitting. Please restart manually.')
exit(1)
if do_break:
break
curr_shape_handle = ret_ints[0]
self.object_handles.append(curr_shape_handle)
if not (self.is_testing and self.test_preset_cases):
time.sleep(0.5)
# we have completed the loop adding all objects!
add_success = len(self.object_handles) == len(self.obj_mesh_ind)
self.prev_obj_positions = []
self.obj_positions = []
# now reposition objects if we are unstacking
if self.task_type == 'unstack':
self.reposition_objects()
def restart_sim(self, connect=False):
if connect:
# Connect to simulator
failure_count = 0
connected = False
while not connected:
vrep.simxFinish(-1) # Just in case, close all opened connections
self.sim_joint_handles = []
self.sim_client = vrep.simxStart('127.0.0.1', self.tcp_port, True, False, 5000, 1) # Connect to V-REP on port 19997
if self.sim_client == -1:
failure_count += 1
print('Failed to connect to simulation (V-REP remote API server) on attempt ' + str(failure_count))
if failure_count > 10:
print('Could not connect, Exiting')
exit(1)
else:
print('Connected to simulation.')
connected = True
# self.restart_sim()
sim_ret, self.UR5_handle = vrep.simxGetObjectHandle(self.sim_client,'UR5',vrep.simx_opmode_blocking)
sim_ret, self.UR5_target_handle = vrep.simxGetObjectHandle(self.sim_client,'UR5_target',vrep.simx_opmode_blocking)
sim_ret, self.UR5_position_goal_target_handle = vrep.simxGetObjectHandle(self.sim_client,'UR5_position_goal_target',vrep.simx_opmode_blocking)
vrep.simxSetObjectPosition(self.sim_client, self.UR5_target_handle, -1, (-0.5,0,0.3), vrep.simx_opmode_blocking)
sim_ok = False
while not sim_ok: # V-REP bug requiring multiple starts and stops to restart
vrep.simxStopSimulation(self.sim_client, vrep.simx_opmode_blocking)
time.sleep(0.5)
sim_started = vrep.simxStartSimulation(self.sim_client, vrep.simx_opmode_blocking)
print('sim started 1: ' + str(sim_started))
time.sleep(0.5)
sim_started = vrep.simxStartSimulation(self.sim_client, vrep.simx_opmode_blocking)
print('sim started 2: ' + str(sim_started))
time.sleep(0.5)
sim_ret, self.UR5_tip_handle = vrep.simxGetObjectHandle(self.sim_client, 'UR5_tip', vrep.simx_opmode_blocking)
# check sim, but we are already in the restart loop so don't recurse
sim_ok = sim_started == vrep.simx_return_ok and self.check_sim(restart_if_not_ok=False)
def check_obj_in_scene(self, obj_handle, workspace_limits=None, buffer_meters=0.1):
"""
Check if object/gripper specified by CoppeliaSim handle is in scene
Arguments:
obj_handle: CoppeliaSim object handle
workspace_limits: Workspace limit coordinates, defaults to self.workspace_limits
buffer_meters: Amount of buffer to allow, defaults to 0.1
"""
if workspace_limits is None:
workspace_limits = self.workspace_limits
# get object position
sim_ret, pos = vrep.simxGetObjectPosition(self.sim_client, obj_handle, -1, vrep.simx_opmode_blocking)
sim_ok = pos[0] > workspace_limits[0][0] - buffer_meters and pos[0] < workspace_limits[0][1] + buffer_meters and pos[1] > workspace_limits[1][0] - buffer_meters and pos[1] < workspace_limits[1][1] + buffer_meters and pos[2] > workspace_limits[2][0] and pos[2] < workspace_limits[2][1]
return sim_ok
def check_sim(self, restart_if_not_ok=True):
# buffer_meters = 0.1 # original buffer value
buffer_meters = 0.1
# Check if simulation is stable by checking if gripper is within workspace
sim_ok = self.check_obj_in_scene(self.UR5_tip_handle)
if restart_if_not_ok and not sim_ok:
print('Simulation unstable. Restarting environment.')
self.restart_sim(connect=True)
self.add_objects()
return sim_ok
def get_task_score(self):
key_positions = np.asarray([[-0.625, 0.125, 0.0], # red
[-0.625, -0.125, 0.0], # blue
[-0.375, 0.125, 0.0], # green
[-0.375, -0.125, 0.0]]) #yellow
obj_positions = np.asarray(self.get_obj_positions())
obj_positions.shape = (1, obj_positions.shape[0], obj_positions.shape[1])
obj_positions = np.tile(obj_positions, (key_positions.shape[0], 1, 1))
key_positions.shape = (key_positions.shape[0], 1, key_positions.shape[1])
key_positions = np.tile(key_positions, (1 ,obj_positions.shape[1] ,1))
key_dist = np.sqrt(np.sum(np.power(obj_positions - key_positions, 2), axis=2))
key_nn_idx = np.argmin(key_dist, axis=0)
return np.sum(key_nn_idx == np.asarray(range(self.num_obj)) % 4)
def check_goal_reached(self):
goal_reached = self.get_task_score() == self.num_obj
return goal_reached
def stop_sim(self):
if self.is_sim:
# Now send some data to V-REP in a non-blocking fashion:
# vrep.simxAddStatusbarMessage(sim_client,'Hello V-REP!',vrep.simx_opmode_oneshot)
# # Start the simulation
# vrep.simxStartSimulation(sim_client,vrep.simx_opmode_oneshot_wait)
# # Stop simulation:
# vrep.simxStopSimulation(sim_client,vrep.simx_opmode_oneshot_wait)
# Before closing the connection to V-REP, make sure that the last command sent out had time to arrive. You can guarantee this with (for example):
vrep.simxGetPingTime(self.sim_client)
# Now close the connection to V-REP:
vrep.simxFinish(self.sim_client)
def get_obj_positions(self, relative_to_handle=-1):
if not self.is_sim:
raise NotImplementedError('get_obj_positions() only supported in simulation, if you are training stacking try specifying --check_z_height')
obj_positions = []
for object_handle in self.object_handles:
sim_ret, object_position = vrep.simxGetObjectPosition(self.sim_client, object_handle, relative_to_handle, vrep.simx_opmode_blocking)
obj_positions.append(object_position)
return obj_positions
def get_objects_in_scene(self, workspace_limits=None, buffer_meters=0.0):
"""
Function to iterate through all object positions and return number of objects within workspace_limits
Returns:
objs: list of CoppeliaSim object handles in scene
"""
if workspace_limits is None:
workspace_limits = self.workspace_limits
# iterate through self.object_handles and check if in scene
return [obj for obj in self.object_handles if self.check_obj_in_scene(obj, workspace_limits=workspace_limits, buffer_meters=buffer_meters)]
def get_obj_positions_and_orientations(self):
if not self.is_sim:
raise NotImplementedError('get_obj_positions_and_orientations() only supported in simulation')
obj_positions = []
obj_orientations = []
for object_handle in self.object_handles:
sim_ret, object_position = vrep.simxGetObjectPosition(self.sim_client, object_handle, -1, vrep.simx_opmode_blocking)
sim_ret, object_orientation = vrep.simxGetObjectOrientation(self.sim_client, object_handle, -1, vrep.simx_opmode_blocking)
obj_positions.append(object_position)
obj_orientations.append(object_orientation)
return obj_positions, obj_orientations
def action_heightmap_coordinate_to_3d_robot_pose(self, x_pixel, y_pixel, action_name, valid_depth_heightmap, robot_push_vertical_offset=0.026):
# Adjust start position of all actions, and make sure z value is safe and not too low
def get_local_region(heightmap, region_width=0.03):
safe_kernel_width = int(np.round((region_width/2)/self.heightmap_resolution))
return heightmap[max(y_pixel - safe_kernel_width, 0):min(y_pixel + safe_kernel_width + 1, heightmap.shape[0]), max(x_pixel - safe_kernel_width, 0):min(x_pixel + safe_kernel_width + 1, heightmap.shape[1])]
finger_width = 0.04
finger_touchdown_region = get_local_region(valid_depth_heightmap, region_width=finger_width)
safe_z_position = self.workspace_limits[2][0]
if finger_touchdown_region.size != 0:
safe_z_position += np.max(finger_touchdown_region)
else:
safe_z_position += valid_depth_heightmap[y_pixel][x_pixel]
if self.background_heightmap is not None:
# add the height of the background scene
safe_z_position += np.max(get_local_region(self.background_heightmap, region_width=0.03))
push_may_contact_something = False
if action_name == 'push':
# determine if the safe z position might actually contact anything during the push action
# TODO(ahundt) common sense push motion region can be refined based on the rotation angle and the direction of travel
push_width = 0.2
local_push_region = get_local_region(valid_depth_heightmap, region_width=push_width)
# push_may_contact_something is True for something noticeably higher than the push action z height
max_local_push_region = np.max(local_push_region)
if max_local_push_region < 0.01:
# if there is nothing more than 1cm tall, there is nothing to push
push_may_contact_something = False
else:
push_may_contact_something = safe_z_position - self.workspace_limits[2][0] + robot_push_vertical_offset < max_local_push_region
# print('>>>> Gripper will push at height: ' + str(safe_z_position) + ' max height of stuff: ' + str(max_local_push_region) + ' predict contact: ' + str(push_may_contact_something))
push_str = ''
if not push_may_contact_something:
push_str += 'Predicting push action failure, heuristics determined '
push_str += 'push at height ' + str(safe_z_position)
push_str += ' would not contact anything at the max height of ' + str(max_local_push_region)
print(push_str)
primitive_position = [x_pixel * self.heightmap_resolution + self.workspace_limits[0][0], y_pixel * self.heightmap_resolution + self.workspace_limits[1][0], safe_z_position]
return primitive_position, push_may_contact_something
def reposition_objects(self, unstack_drop_height=0.05, action_log=None, logger=None,
goal_condition=None, workspace_limits=None):
# grasp blocks from previously placed positions and place them in a random position.
if self.place_task and self.unstack:
print("------- UNSTACKING --------")
if len(self.place_pose_history) == 0:
print("NO PLACE HISTORY TO UNSTACK YET.")
print("HUMAN, PLEASE MOVE BLOCKS AROUND")
print("SLEEPING FOR 10 SECONDS")
for i in range(10):
print("SLEEPING FOR %d" % (10 - i))
time.sleep(1)
print("-------- RESUMING AFTER MANUAL UNSTACKING --------")
place_pose_history = self.place_pose_history.copy()
place_pose_history.reverse()
# unstack the block on the bottom of the stack so that the robot doesn't keep stacking in the same spot.
place_pose_history.append(place_pose_history[-1])
holding_object = not(self.close_gripper())
# if already has an object in the gripper when reposition objects gets called, place that object somewhere random
if holding_object:
_, _, rand_position, rand_orientation = self.generate_random_object_pose()
rand_position[2] = unstack_drop_height # height from which to release blocks (0.05 m per block)
rand_angle = rand_orientation[0]
self.place(rand_position, rand_angle, save_history=False)
else:
self.open_gripper()
# go to x,y position of previous places and pick up the max_z height from the depthmap (top of the stack)
for pose in place_pose_history:
x, y, z, angle = pose
valid_depth_heightmap, color_heightmap, depth_heightmap, max_z_height, color_img, depth_img = self.get_camera_data(return_heightmaps=True)
# get depth_heightmap pixel_coordinates of where the previous place was
x_pixel = int((x - self.workspace_limits[0][0]) / self.heightmap_resolution)
x_pixel = min(x_pixel, 223) # prevent indexing outside the heightmap bounds
y_pixel = int((y - self.workspace_limits[1][0]) / self.heightmap_resolution)
y_pixel = min(y_pixel, 223)
primitive_position, _ = self.action_heightmap_coordinate_to_3d_robot_pose(x_pixel, y_pixel, 'grasp', valid_depth_heightmap)
# this z position is checked based on the x,y position of the robot. Previously, the z height was the max z_height in the depth_heightmap
# plus an offset. There
z = primitive_position[2]
grasp_success, color_success = self.grasp([x, y, z], angle)
if grasp_success:
_, _, rand_position, rand_orientation = self.generate_random_object_pose()
rand_position[2] = unstack_drop_height # height from which to release blocks (0.05 m per block)
rand_angle = rand_orientation[0]
self.place(rand_position, rand_angle, save_history=False)
# clear the place hisory after unstacking
self.place_pose_history = []
print("------- UNSTACKING COMPLETE --------")
else:
if self.is_sim:
# Move gripper out of the way to the home position
success = self.go_home()
if not success:
return success
# sim_ret, UR5_target_handle = vrep.simxGetObjectHandle(self.sim_client,'UR5_target',vrep.simx_opmode_blocking)
# vrep.simxSetObjectPosition(self.sim_client, UR5_target_handle, -1, (-0.5,0,0.3), vrep.simx_opmode_blocking)
# time.sleep(1)
# if not unstacking, place all objects randomly
if self.task_type is None or self.task_type != 'unstack':
for object_handle in self.object_handles:
# Drop object at random x,y location and random orientation in robot workspace
self.reposition_object_randomly(object_handle)
time.sleep(0.5)
# if unstacking, need to create a stack at a random location
else:
successful_stack = False
while not successful_stack:
# get random obj pose
_, _, obj_pos, obj_ori = self.generate_random_object_pose()
obj_ori[:2] = [0, 0]
# iterate through remaining object handles and place them on top of existing stack (randomize order)
obj_handles_rand = np.arange(len(self.object_handles))
np.random.shuffle(obj_handles_rand)
for ind, i in enumerate(obj_handles_rand):
# reposition object as (x,y) position of first block, set z pos depending on stack height
# same orientation (TODO(adit98) add noise later?)
obj_pos[-1] = ind * 0.06 + 0.05
# reposition object
self.reposition_object_at_list_index_to_location(obj_pos, obj_ori, i)
# regenerate object orientation and keep only the top block rotation
_, _, _, obj_ori = self.generate_random_object_pose()
obj_ori[:2] = [0, 0]
# wait for objects to settle
time.sleep(0.75)
# continue to retry until we have a successful stack of 4 blocks
successful_stack, stack_height = self.check_stack(np.ones(len(self.object_handles)))
print('reposition_objects(): successful stack:', successful_stack, 'stack_height:', stack_height)
if stack_height >= len(self.object_handles):
successful_stack = True
# an extra half second so things settle down
time.sleep(0.5)
return True
def get_camera_data(self, workspace_limits=None, heightmap_resolution=None, return_heightmaps=False, go_home=True, z_height_retake_threshold=0.3, median_filter_size=5, color_median_filter_size=5):
"""
# Returns
[valid_depth_heightmap, color_heightmap, depth_heightmap, max_z_height, color_img, depth_img] if return_heightmaps is True, otherwise [color_img, depth_img]
"""
if workspace_limits is None:
workspace_limits = self.workspace_limits
if heightmap_resolution is None:
heightmap_resolution = self.heightmap_resolution
max_z_height = np.inf
if go_home:
self.go_home(block_until_home=True)
def get_color_depth():
""" Get the raw color and depth images
"""
if self.is_sim:
sim_ret = None
while sim_ret != vrep.simx_return_ok:
# Get color image from simulation
sim_ret, resolution, raw_image = vrep.simxGetVisionSensorImage(self.sim_client, self.cam_handle, 0, vrep.simx_opmode_blocking)
color_img = np.asarray(raw_image)
color_img.shape = (resolution[1], resolution[0], 3)
color_img = color_img.astype(np.float)/255
color_img[color_img < 0] += 1
color_img *= 255
color_img = np.fliplr(color_img)
color_img = color_img.astype(np.uint8)
sim_ret = None
while sim_ret != vrep.simx_return_ok:
# Get depth image from simulation
sim_ret, resolution, depth_buffer = vrep.simxGetVisionSensorDepthBuffer(self.sim_client, self.cam_handle, vrep.simx_opmode_blocking)
depth_img = np.asarray(depth_buffer)
depth_img.shape = (resolution[1], resolution[0])
depth_img = np.fliplr(depth_img)
zNear = 0.01
zFar = 10
depth_img = depth_img * (zFar - zNear) + zNear
else:
# prevent camera from taking a picture while the robot is still in the frame.
# Get color and depth image from ROS service
color_img, depth_img = self.camera.get_data()
depth_img = depth_img.astype(float) / 1000 # unit: mm -> meter
# color_img = self.camera.color_data.copy()
# depth_img = self.camera.depth_data.copy()
return color_img, depth_img
color_img, depth_img = get_color_depth() # unit: mm -> meter
if return_heightmaps:
# this allows the error to print only once, so it doesn't spam the console.
print_error = 0
while max_z_height > z_height_retake_threshold:
scaled_depth_img = depth_img * self.cam_depth_scale # Apply depth scale from calibration
color_heightmap, depth_heightmap = utils.get_heightmap(color_img, scaled_depth_img, self.cam_intrinsics, self.cam_pose,
workspace_limits, heightmap_resolution, background_heightmap=self.background_heightmap,
median_filter_pixels=median_filter_size, color_median_filter_pixels=color_median_filter_size)
# TODO(ahundt) switch to masked array, then only have a regular heightmap
valid_depth_heightmap = depth_heightmap.copy()
valid_depth_heightmap[np.isnan(valid_depth_heightmap)] = 0
_, max_z_height, _ = self.check_z_height(valid_depth_heightmap, reward_multiplier=1)
# If just manipulating blocks for dataset image generation, no need to check height.
if self.logoblock_dataset:
break
if max_z_height > z_height_retake_threshold:
if print_error > 3:
print('ERROR: depth_heightmap value too high. '
'Use the UR5 teach mode to move the robot manually to the home position. '
'max_z_height: ', max_z_height)
# Get color and depth image from ROS service
color_img, depth_img = get_color_depth()
print_error += 1
time.sleep(0.1)
return valid_depth_heightmap, color_heightmap, depth_heightmap, max_z_height, color_img, depth_img
# if not return_depthmaps, return just raw images
return color_img, depth_img
def parse_tcp_state_data(self, state_data, subpackage):
"""
state_data: 'joint_data', 'cartesian_info', 'force_mode_data', 'tool_data'
"""
# Read package header
data_bytes = bytearray()
data_bytes.extend(state_data)
data_length = struct.unpack("!i", data_bytes[0:4])[0];
robot_message_type = data_bytes[4]
assert(robot_message_type == 16)
byte_idx = 5
# Parse sub-packages
subpackage_types = {'joint_data' : 1, 'cartesian_info' : 4, 'force_mode_data' : 7, 'tool_data' : 2}
while byte_idx < data_length:
# package_length = int.from_bytes(data_bytes[byte_idx:(byte_idx+4)], byteorder='big', signed=False)
package_length = struct.unpack("!i", data_bytes[byte_idx:(byte_idx+4)])[0]
byte_idx += 4
package_idx = data_bytes[byte_idx]
if package_idx == subpackage_types[subpackage]:
byte_idx += 1
break
byte_idx += package_length - 4
def parse_joint_data(data_bytes, byte_idx):
actual_joint_positions = [0,0,0,0,0,0]
target_joint_positions = [0,0,0,0,0,0]
for joint_idx in range(6):
actual_joint_positions[joint_idx] = struct.unpack('!d', data_bytes[(byte_idx+0):(byte_idx+8)])[0]
target_joint_positions[joint_idx] = struct.unpack('!d', data_bytes[(byte_idx+8):(byte_idx+16)])[0]
byte_idx += 41
return actual_joint_positions
def parse_cartesian_info(data_bytes, byte_idx):
actual_tool_pose = [0,0,0,0,0,0]
for pose_value_idx in range(6):
actual_tool_pose[pose_value_idx] = struct.unpack('!d', data_bytes[(byte_idx+0):(byte_idx+8)])[0]
byte_idx += 8
return actual_tool_pose
def parse_tool_data(data_bytes, byte_idx):
byte_idx += 2
tool_analog_input2 = struct.unpack('!d', data_bytes[(byte_idx+0):(byte_idx+8)])[0]
return tool_analog_input2
parse_functions = {'joint_data' : parse_joint_data, 'cartesian_info' : parse_cartesian_info, 'tool_data' : parse_tool_data}
return parse_functions[subpackage](data_bytes, byte_idx)
def parse_rtc_state_data(self, state_data):
# Read package header
data_bytes = bytearray()
data_bytes.extend(state_data)
data_length = struct.unpack("!i", data_bytes[0:4])[0]
assert(data_length == 812)
byte_idx = 4 + 8 + 8*48 + 24 + 120
TCP_forces = [0,0,0,0,0,0]