-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathSMACH_takeshi_TASK2.py
1935 lines (1476 loc) · 67.8 KB
/
SMACH_takeshi_TASK2.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
#!/usr/bin/env python
from std_srvs.srv import Empty, Trigger, TriggerRequest
import smach
from std_msgs.msg import String
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from geometry_msgs.msg import PoseStamped, Point , Quaternion
from actionlib_msgs.msg import GoalStatus
import moveit_commander
import moveit_msgs.msg
import tf2_ros
from tf2_sensor_msgs.tf2_sensor_msgs import do_transform_cloud
from object_classification.srv import *
from sensor_msgs.msg import Image as ImageMsg
from cv_bridge import CvBridge, CvBridgeError
from utils_notebooks import *
from utils_takeshi import *
########## Functions for takeshi states ##########
class Proto_state(smach.State):###example of a state definition.
def __init__(self):
smach.State.__init__(self,outcomes=['succ','failed','tries'])
self.tries=0
def execute(self,userdata):
rospy.loginfo('State : PROTO_STATE')
if self.tries==3:
self.tries=0
return'tries'
if succ:
return 'succ'
else:
return 'failed'
global trans_hand
self.tries+=1
if self.tries==3:
self.tries=0
return'tries'
####################################################################Functions in notebook ##################################################################
def messg_class_name_idx(message_read,class_resp):
txt=message_read.split('_')
txt=''.join(txt)
print (type(class_resp))
for i,name in enumerate(class_names):
if txt in name:
print(name , i)
idx=i
if len(np.where(class_resp==idx)[0])==0:
print('requeste class not found, porceed to closest tf')
return False
if len(np.where(class_resp==idx)[0])==1:
print('requeste class is tf index ', np.where(class_resp==idx)[0]/3)
return np.where(class_resp==idx)[0]/3
if len(np.where(class_resp==idx)[0])>1:
new_class_resp=class_resp.reshape(len(class_resp)/3,3)
if len(np.where(new_class_resp[:,0]==idx)[0])==1:
print('requested class is tf index ', np.where(new_class_resp==idx)[0]/3)
else: return 'failed'
def readmssg(message):
global message_read
message_read=message.data
return message_read
def primitive_grasp_detector():
a = gripper.get_current_joint_values()
if np.linalg.norm(a - np.asarray(grasped)) > (np.linalg.norm(a - np.asarray(ungrasped))):
print ('grasp seems to have failed')
return False
else:
print('super primitive grasp detector points towards succesfull ')
return True
def cents_to_sceneobjs(cents):
trans , rot = listener.lookupTransform('/map', '/head_rgbd_sensor_gazebo_frame', rospy.Time(0))
for i ,cent in enumerate(cents):
x,y,z=cent
if np.isnan(x) or np.isnan(y) or np.isnan(z):
print('nan','error')
return False
else:
broadcaster.sendTransform((x,y,z),rot, rospy.Time.now(), 'Closest_Object'+str(i),"head_rgbd_sensor_link")
rospy.sleep(.2)
xyz_map,cent_quat= listener.lookupTransform('/map', 'Closest_Object'+str(i),rospy.Time(0))
map_euler=tf.transformations.euler_from_quaternion(cent_quat)
rospy.sleep(.2)
p = PoseStamped()
p.header.frame_id = "map" # "head_rgbd_sensor_link"
p.pose.position.x = xyz_map[0]
p.pose.position.y = xyz_map[1]
p.pose.position.z = xyz_map[2]
p.pose.orientation.x = 0.5 * np.pi
p.pose.orientation.w = 0.5 * np.pi
scene.add_box('obs'+str(i),p,(.1,.1,.1) )
return True
def find_category(dictionary, name):
if name in dictionary:
category=dictionary[name]
else: #go to Bin B
category = 6
return category
#To Do:
#To Do: pack them in an utils file
def save_hand(i=0):
img_msg = rospy.wait_for_message('/hsrb/hand_camera/image_raw', ImageMsg)
cv2_img = bridge.imgmsg_to_cv2(img_msg, "bgr8")
img = np.asarray (cv2_img)
np.save('hand_camera_rgb_'+str(i)+'.npy',cv2_img)
print ('saving hand cam img')
def add_object(name, size, pose, orientation):
p = PoseStamped()
p.header.frame_id = "map" # "head_rgbd_sensor_link"
p.pose.position.x = pose[0]
p.pose.position.y = pose[1]
p.pose.position.z = pose[2]
p.pose.orientation.x = orientation[0] * np.pi
p.pose.orientation.y = orientation[1] * np.pi
p.pose.orientation.z = orientation[2] * np.pi
p.pose.orientation.w = orientation[3] * np.pi
scene.add_box(name, p, size)
def add_transform(child, trans, rot, parent="map"):
static_transformStamped = TransformStamped()
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = parent
static_transformStamped.child_frame_id = child
static_transformStamped.transform.translation.x = trans[0]
static_transformStamped.transform.translation.y = trans[1]
static_transformStamped.transform.translation.z = trans[2]
static_transformStamped.transform.rotation.x = rot[0]
static_transformStamped.transform.rotation.y = rot[1]
static_transformStamped.transform.rotation.z = rot[2]
static_transformStamped.transform.rotation.w = rot[3]
tf_static_broadcaster.sendTransform(static_transformStamped)
def publish_scene():
add_object("shelf", [1.5, 0.04, 0.4], [2.5, 4.85, 0.78], [0.5,0,0,0.5])
add_object("shelf1", [1.5, 0.04, 0.4], [2.5, 4.85, 0.49], [0.5,0,0, 0.5])
add_object("shelf2", [1.5, 0.04, 0.4], [2.5, 4.85, 0.18], [0.5,0,0, 0.5])
#add_object("shelf_wall", [1, 1, 0.04], [2.5, 4.9, 0.5], [0.5,0,0, 0.5])
add_object("shelf_wall1", [.04, 1, 0.4], [2.65, 4.9, 0.5],[0.5,0,0, 0.5])
add_object("shelf_wall2", [.04, 1, 0.4], [1.85, 4.9, 0.5], [0.5,0,0 ,0.5])
add_object("table_big", [1.5, 0.3, 0.5], [0.95, 1.9, 0.34], [0.5,0,0, 0.5])
add_object("table_big_legs1",[.01,.6,.2], [1.55,1.8,0.1], [0.5,0,0, 0.5])
add_object("table_big_legs2",[.01,.6,.2], [0.45,1.8,0.1], [0.5,0,0 ,0.5])
add_object("table_small", [0.9, 0.02, 0.4], [-0.2, 1.85, 0.61], [0.5,0,0 ,0.5])
add_object("table_small_legs1",[.01,.6,.2], [-0.3,1.75,0.3], [0.5,0,0, 0.5])
add_object("table_small_legs2",[.01,.6,.2], [0.1,1.75,0.3], [0.5,0,0 ,0.5])
add_object("table_tray", [0.65, 0.01, 0.7], [1.8, -0.65, 0.4], [0.5,0,0, 0.5])
add_object("containers", [0.3, 0.3, 0.3], [1.4, -0.65, 0.4], [0.5,0,0, 0.5])
add_object("drawers", [1, 1, 1], [0, -0.65, 0.5], [0.5,0,0, 0.5])
add_object("big_wall" , [6.0, 0.2, 1.2], [3.2, 2.0, 0.0], [0,0.0,0.5 ,0.5])
add_object("mid_wall" , [4.0, 0.2, 1.2], [0.1, 2.1, 0.0], [0,0.0,0.0 ,1/np.pi])
add_object("door_wall" , [5.0, 0.2, 0.2], [-0.8, 2.8, 0.0], [0,0.0,0.5 ,0.5 ])
add_object("close_wall", [4.0, 0.2, 0.2], [1.1, -0.5, 0.0], [0,0.0,0.0 ,1/np.pi])
add_object("far_wall", [4.0, 0.2, 0.2], [1.1, 5.0, 0.0], [0,0.0,0.0 ,1/np.pi])
add_transform("Tray_A", [1.665, -0.59, 0.4], [0, 0, 0, 1])
add_transform("Tray_B", [1.97, -0.59, 0.4], [0, 0, 0, 1])
static_transformStamped=TransformStamped()
##FIXING TF TO MAP ( ODOM REALLY)
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = "map"
static_transformStamped.child_frame_id = "Drawer_low"
static_transformStamped.transform.translation.x = 0.14
static_transformStamped.transform.translation.y = -0.344
static_transformStamped.transform.translation.z = 0.27
static_transformStamped.transform.rotation.x = 0
static_transformStamped.transform.rotation.y = 0
static_transformStamped.transform.rotation.z = 0
static_transformStamped.transform.rotation.w = 1
tf_static_broadcaster.sendTransform(static_transformStamped)
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = "map"
static_transformStamped.child_frame_id = "Box1"
static_transformStamped.transform.translation.x = 2.3
static_transformStamped.transform.translation.y = -0.5
static_transformStamped.transform.translation.z = .5
static_transformStamped.transform.rotation.x = 0
static_transformStamped.transform.rotation.y = 0
static_transformStamped.transform.rotation.z = 0
static_transformStamped.transform.rotation.w = 1
tf_static_broadcaster.sendTransform(static_transformStamped)
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = "map"
static_transformStamped.child_frame_id = "Drawer_left"
static_transformStamped.transform.translation.x = .48
static_transformStamped.transform.translation.y = -0.39
static_transformStamped.transform.translation.z = .27
static_transformStamped.transform.rotation.y = 0
static_transformStamped.transform.rotation.z = 0
static_transformStamped.transform.rotation.w = 1
tf_static_broadcaster.sendTransform(static_transformStamped)
static_transformStamped = TransformStamped()
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = "map"
static_transformStamped.child_frame_id = "Drawer_high"
static_transformStamped.transform.translation.x = 0.14
static_transformStamped.transform.translation.y = -0.39
static_transformStamped.transform.translation.z = 0.52
static_transformStamped.transform.rotation.x = 0
static_transformStamped.transform.rotation.y = 0
static_transformStamped.transform.rotation.z = 0
static_transformStamped.transform.rotation.w = 1
tf_static_broadcaster.sendTransform(static_transformStamped)
return True
def get_current_time_sec():
return rospy.Time.now().to_sec()
def move_abs(vx,vy,vw, time=0.05):
start_time = get_current_time_sec()
while get_current_time_sec() - start_time < time:
twist = Twist()
twist.linear.x = vx
twist.linear.y = vy
twist.angular.z = vw / 180.0 * np.pi
base_vel_pub.publish(twist)
def pose_2_np(wp_p):
#Takes a pose message and returns array
return np.asarray((wp_p.pose.position.x,wp_p.pose.position.y,wp_p.pose.position.z)) , np.asarray((wp_p.pose.orientation.w,wp_p.pose.orientation.x,wp_p.pose.orientation.y, wp_p.pose.orientation.z))
def np_2_pose(position,orientation):
#Takes a pose np array and returns pose message
wb_p= geometry_msgs.msg.PoseStamped()
wb_p.pose.position.x= position[0]
wb_p.pose.position.y= position[1]
wb_p.pose.position.z= position[2]
wb_p.pose.orientation.w= orientation[0]
wb_p.pose.orientation.x= orientation[1]
wb_p.pose.orientation.y= orientation[2]
wb_p.pose.orientation.z= orientation[3]
return wb_p
def open_gripper():
target_motor=1
gripper.set_start_state_to_current_state()
try:
gripper.set_joint_value_target({'hand_motor_joint':target_motor})
except:
print('OOB')
succ=gripper.go()
def close_gripper():
target_motor=0.0
gripper.set_start_state_to_current_state()
try:
gripper.set_joint_value_target({'hand_motor_joint':target_motor})
except:
print('OOB')
succ=gripper.go()
def correct_points(low=.27,high=1000):
#Corrects point clouds "perspective" i.e. Reference frame head is changed to reference frame map
data = rospy.wait_for_message('/hsrb/head_rgbd_sensor/depth_registered/rectified_points', PointCloud2)
np_data=ros_numpy.numpify(data)
trans,rot=listener.lookupTransform('/map', '/head_rgbd_sensor_gazebo_frame', rospy.Time(0))
eu=np.asarray(tf.transformations.euler_from_quaternion(rot))
t=TransformStamped()
rot=tf.transformations.quaternion_from_euler(-eu[1],0,0)
t.header.stamp = data.header.stamp
t.transform.rotation.x = rot[0]
t.transform.rotation.y = rot[1]
t.transform.rotation.z = rot[2]
t.transform.rotation.w = rot[3]
cloud_out = do_transform_cloud(data, t)
np_corrected=ros_numpy.numpify(cloud_out)
corrected=np_corrected.reshape(np_data.shape)
img= np.copy(corrected['y'])
img[np.isnan(img)]=2
img3 = np.where((img>low)&(img< 0.99*(trans[2])),img,255)
return img3
def plane_seg_square_imgs(lower=500 ,higher=50000,reg_ly= 30,reg_hy=600,reg_lx=0,reg_hx=1000,plt_images=True):
#Segment Plane using corrected point cloud
#Lower, higher = min, max area of the box
#reg_ly= 30,reg_hy=600 Region (low y region high y ) Only centroids within region are accepted
image= rgbd.get_h_image()
iimmg= rgbd.get_image()
points_data= rgbd.get_points()
img=np.copy(image)
img3= correct_points()
_,contours, hierarchy = cv2.findContours(img3.astype('uint8'),cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE)
i=0
cents=[]
points=[]
images=[]
for i, contour in enumerate(contours):
area = cv2.contourArea(contour)
if area > lower and area < higher :
M = cv2.moments(contour)
# calculate x,y coordinate of center
cX = int(M["m10"] / M["m00"])
cY = int(M["m01"] / M["m00"])
boundRect = cv2.boundingRect(contour)
#just for drawing rect, dont waste too much time on this
image_aux= iimmg[boundRect[1]:boundRect[1]+max(boundRect[2],boundRect[3]),boundRect[0]:boundRect[0]+max(boundRect[2],boundRect[3])]
images.append(image_aux)
img=cv2.rectangle(img,(boundRect[0], boundRect[1]),(boundRect[0]+boundRect[2], boundRect[1]+boundRect[3]), (0,0,0), 2)
# calculate moments for each contour
if (cY > reg_ly and cY < reg_hy and cX > reg_lx and cX < reg_hx ):
cv2.circle(img, (cX, cY), 5, (255, 255, 255), -1)
cv2.putText(img, "centroid_"+str(i)+"_"+str(cX)+','+str(cY) , (cX - 25, cY - 25) ,cv2.FONT_HERSHEY_SIMPLEX, 0.9, (0, 0, 0), 2)
#print ('cX,cY',cX,cY)
xyz=[]
for jy in range (boundRect[0], boundRect[0]+boundRect[2]):
for ix in range(boundRect[1], boundRect[1]+boundRect[3]):
aux=(np.asarray((points_data['x'][ix,jy],points_data['y'][ix,jy],points_data['z'][ix,jy])))
if np.isnan(aux[0]) or np.isnan(aux[1]) or np.isnan(aux[2]):
'reject point'
else:
xyz.append(aux)
xyz=np.asarray(xyz)
cent=xyz.mean(axis=0)
cents.append(cent)
#print (cent)
points.append(xyz)
sub_plt=0
if plt_images:
for image in images:
sub_plt+=1
ax = plt.subplot(5, 5, sub_plt )
##plt.imshow(image)
#plt.axis("off")
cents=np.asarray(cents)
### returns centroids found and a group of 3d coordinates that conform the centroid
return(cents,np.asarray(points), images)
def seg_square_imgs(lower=2000,higher=50000,reg_ly=0,reg_hy=1000,reg_lx=0,reg_hx=1000,plt_images=False):
#Using kmeans for image segmentation find
#Lower, higher = min, max area of the box
#reg_ly= 30,reg_hy=600,reg_lx=0,reg_hx=1000, Region (low x,y region high x,y ) Only centroids within region are accepted
image= rgbd.get_h_image()
iimmg= rgbd.get_image()
points_data= rgbd.get_points()
values=image.reshape((-1,3))
values= np.float32(values)
criteria= ( cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER ,1000,0.1)
k=6
_ , labels , cc =cv2.kmeans(values , k ,None,criteria,30,cv2.KMEANS_RANDOM_CENTERS)
cc=np.uint8(cc)
segmented_image= cc[labels.flatten()]
segmented_image=segmented_image.reshape(image.shape)
th3 = cv2.adaptiveThreshold(segmented_image,255,cv2.ADAPTIVE_THRESH_GAUSSIAN_C,cv2.THRESH_BINARY,11,2)
kernel = np.ones((5,5),np.uint8)
im4=cv2.erode(th3,kernel,iterations=4)
plane_mask=points_data['z']
cv2_img=plane_mask.astype('uint8')
img=im4
_,contours, hierarchy = cv2.findContours(im4.astype('uint8'),cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE)
i=0
cents=[]
points=[]
images=[]
for i, contour in enumerate(contours):
area = cv2.contourArea(contour)
if area > lower and area < higher :
M = cv2.moments(contour)
# calculate x,y coordinate of center
cX = int(M["m10"] / M["m00"])
cY = int(M["m01"] / M["m00"])
boundRect = cv2.boundingRect(contour)
#just for drawing rect, dont waste too much time on this
image_aux= iimmg[boundRect[1]:boundRect[1]+max(boundRect[3],boundRect[2]),boundRect[0]:boundRect[0]+max(boundRect[3],boundRect[2])]
images.append(image_aux)
img=cv2.rectangle(img,(boundRect[0], boundRect[1]),(boundRect[0]+boundRect[2], boundRect[1]+boundRect[3]), (0,0,0), 2)
#img=cv2.rectangle(img,(boundRect[0], boundRect[1]),(boundRect[0]+max(boundRect[2],boundRect[3]), boundRect[1]+max(boundRect[2],boundRect[3])), (0,0,0), 2)
# calculate moments for each contour
if (cY > reg_ly and cY < reg_hy and cX > reg_lx and cX < reg_hx ):
cv2.circle(img, (cX, cY), 5, (255, 255, 255), -1)
cv2.putText(img, "centroid_"+str(i)+"_"+str(cX)+','+str(cY) , (cX - 25, cY - 25) ,cv2.FONT_HERSHEY_SIMPLEX, 0.9, (0, 0, 0), 2)
#print ('cX,cY',cX,cY)
xyz=[]
for jy in range (boundRect[0], boundRect[0]+boundRect[2]):
for ix in range(boundRect[1], boundRect[1]+boundRect[3]):
aux=(np.asarray((points_data['x'][ix,jy],points_data['y'][ix,jy],points_data['z'][ix,jy])))
if np.isnan(aux[0]) or np.isnan(aux[1]) or np.isnan(aux[2]):
'reject point'
else:
xyz.append(aux)
xyz=np.asarray(xyz)
cent=xyz.mean(axis=0)
cents.append(cent)
#print (cent)
points.append(xyz)
else:
#print ('cent out of region... rejected')
images.pop()
sub_plt=0
if plt_images:
for image in images:
sub_plt+=1
ax = plt.subplot(5, 5, sub_plt )
plt.imshow(image)
plt.axis("off")
cents=np.asarray(cents)
#images.append(img)
return(cents,np.asarray(points), images)
def gaze_point(x,y,z):
###Moves head to make center point of rgbd image th coordinates w.r.t.map
### To do: (Start from current pose instead of always going to neutral first )
head_pose = head.get_current_joint_values()
head_pose[0]=0.0
head_pose[1]=0.0
head.set_joint_value_target(head_pose)
head.go()
trans , rot = listener.lookupTransform('/map', '/head_rgbd_sensor_gazebo_frame', rospy.Time(0)) #
# arm_pose=arm.get_current_joint_values()
# arm_pose[0]=.1
# arm_pose[1]= -0.3
# arm.set_joint_value_target(arm_pose)
# arm.go()
e =tf.transformations.euler_from_quaternion(rot)
#print('i am at',trans,np.rad2deg(e)[2])
#print('gaze goal',x,y,z)
#tf.transformations.euler_from_quaternion(rot)
x_rob,y_rob,z_rob,th_rob= trans[0], trans[1] ,trans[2] , e[2]
D_x=x_rob-x
D_y=y_rob-y
D_z=z_rob-z
D_th= np.arctan2(D_y,D_x)
#print('relative to robot',(D_x,D_y,np.rad2deg(D_th)))
pan_correct= (- th_rob + D_th + np.pi) % (2*np.pi)
if(pan_correct > np.pi):
pan_correct=-2*np.pi+pan_correct
if(pan_correct < -np.pi):
pan_correct=2*np.pi+pan_correct
if ((pan_correct) > .5 * np.pi):
print ('Exorcist alert')
pan_correct=.5*np.pi
head_pose[0]=pan_correct
tilt_correct=np.arctan2(D_z,np.linalg.norm((D_x,D_y)))
head_pose [1]=-tilt_correct
head.set_joint_value_target(head_pose)
succ=head.go()
return succ
"""def move_base_goal(x, y, theta):
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.pose.position.x = x
goal.target_pose.pose.position.y = y
goal.target_pose.pose.orientation = quaternion_from_euler(0, 0, theta)
navclient.send_goal(goal)
navclient.wait_for_result()
state = navclient.get_state()
return True if state == 3 else False"""
def move_base(x,y,theta,time_out=20):
#using nav client and toyota navigation go to x,y,yaw
#To Do: PUMAS NAVIGATION
#pose = PoseStamped()
#pose.header.stamp = rospy.Time(0)
#pose.header.frame_id = "map"
#pose.pose.position = Point(goal_x, goal_y, 0)
#quat = tf.transformations.quaternion_from_euler(0, 0, goal_yaw)
#pose.pose.orientation = Quaternion(*quat)
# create a MOVE BASE GOAL
print ('MOVING TO ', x,y,theta)
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.pose.position.x = x
goal.target_pose.pose.position.y = y
goal.target_pose.pose.orientation = quaternion_from_euler(0, 0, theta*180/np.pi)
navclient.send_goal(goal)
navclient.wait_for_result(timeout=rospy.Duration(time_out))
state = navclient.get_state()
return True if state == 3 else False
def static_tf_publish(cents):
## Publish tfs of the centroids obtained w.r.t. head sensor frame and references them to map (static)
trans , rot = listener.lookupTransform('/map', '/base_link', rospy.Time(0))
#closest_centroid_index= np.argmin(np.linalg.norm(trans-cents, axis=1))##CLOSEST CENTROID
closest_centroid_index=0
min_D_to_base=10
for i ,cent in enumerate(cents):
x,y,z=cent
if np.isnan(x) or np.isnan(y) or np.isnan(z):
print('nan')
else:
broadcaster.sendTransform((x,y,z),rot, rospy.Time.now(), 'Object'+str(i),"head_rgbd_sensor_link")
rospy.sleep(.2)
xyz_map,cent_quat= listener.lookupTransform('/map', 'Object'+str(i),rospy.Time(0))
D_to_base=np.linalg.norm(np.asarray(trans)[:2]-np.asarray(xyz_map)[:2])
if D_to_base <= min_D_to_base:
min_D_to_base=D_to_base
closest_centroid_index=i
closest_centroid_height= xyz_map[2]
print ('D Base to obj - ',i, np.linalg.norm(np.asarray(trans)[:2]-np.asarray(xyz_map)[:2]))
i = closest_centroid_index
xyz_map,cent_quat= listener.lookupTransform('/map', 'Object'+str(i),rospy.Time(0))
print ('height closest centroid map',xyz_map[2])
map_euler=tf.transformations.euler_from_quaternion(cent_quat)
rospy.sleep(.2)
static_transformStamped = TransformStamped()
##FIXING TF TO MAP ( ODOM REALLY)
#tf_broadcaster1.sendTransform( (xyz[0],xyz[1],xyz[2]),tf.transformations.quaternion_from_euler(0, 0, 0), rospy.Time(0), "obj"+str(ind), "head_rgbd_sensor_link")
static_transformStamped.header.stamp = rospy.Time.now()
static_transformStamped.header.frame_id = "map"
static_transformStamped.transform.translation.x = float(xyz_map[0])
static_transformStamped.transform.translation.y = float(xyz_map[1])
static_transformStamped.transform.translation.z = float(xyz_map[2])
#quat = tf.transformations.quaternion_from_euler(-euler[0],0,1.5)
static_transformStamped.transform.rotation.x = 0#-quat[0]#trans.transform.rotation.x
static_transformStamped.transform.rotation.y = 0#-quat[1]#trans.transform.rotation.y
static_transformStamped.transform.rotation.z = 0#-quat[2]#trans.transform.rotation.z
static_transformStamped.transform.rotation.w = 1#-quat[3]#trans.transform.rotation.w
print ('xyz_map',xyz_map)
if xyz_map[2] > 0.8 : #and xyz_map[2] < 1.3:
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Shelf_high"
tf_static_broadcaster.sendTransform(static_transformStamped)
if xyz_map[2] > 0.5 and xyz_map[2] < 0.7 : #and xyz_map[2] < 1.3:
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Shelf_low"
tf_static_broadcaster.sendTransform(static_transformStamped)
if xyz_map[2] > 0.7 and xyz_map[2] < 0.79:
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Table_real_lab"
tf_static_broadcaster.sendTransform(static_transformStamped)
if xyz_map[2] > .4 and xyz_map[2] < .46: #table 1
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Table_1"
tf_static_broadcaster.sendTransform(static_transformStamped)
if xyz_map[2] < .25: #Floor
if xyz_map[1] < 1.56:
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Floor"
tf_static_broadcaster.sendTransform(static_transformStamped)
if xyz_map[1] >= 1.56:
static_transformStamped.child_frame_id = "Object_"+str(i)+"_Floor_"+"risky"
tf_static_broadcaster.sendTransform(static_transformStamped)
return closest_centroid_height, closest_centroid_index
def move_d_to(target_distance=0.5,target_link='Floor_Object0'):
###Face towards Targetlink and get target distance close
try:
obj_tar,_ = listener.lookupTransform('map',target_link,rospy.Time(0))
except(tf.LookupException):
print ('no tf found')
return False
robot, _ = listener.lookupTransform('map','base_link',rospy.Time(0))
pose, quat = listener.lookupTransform('base_link',target_link,rospy.Time(0))
euler=euler_from_quaternion(quat)
D=np.asarray(obj_tar)-np.asarray(robot)
d=D/np.linalg.norm(D)
if target_distance==-1:
new_pose=np.asarray(robot)
else:
new_pose=(np.asarray(obj_tar)-target_distance*d)
broadcaster.sendTransform(new_pose,(0,0,0,1), rospy.Time.now(), 'D_from_object','map')
#for_grasp=new_pose
#for_grasp[0]+=.15* np.sin( np.arctan2(pose[1],pose[0])-euler[2])
#for_grasp[1]+=.15* np.cos( np.arctan2(pose[1],pose[0])-euler[2])
#broadcaster.sendTransform(for_grasp,(0,0,0,1), rospy.Time.now(), 'D_from_object_grasp_floor','map')
wb_v= whole_body.get_current_joint_values()
arm.set_named_target('go')
arm.go()
print('EULER, WBV', euler_from_quaternion(quat), wb_v[2])
#succ=move_base( for_grasp[0],for_grasp[1], np.arctan2(pose[1],pose[0])-euler[2])
succ=move_base( new_pose[0],new_pose[1], np.arctan2(pose[1],pose[0]) -euler[2] -0.07 )
return succ
def classify_images(images, target='None'):
req=classify_client.request_class()
for image in images:
img_msg=bridge.cv2_to_imgmsg(image)
req.in_.image_msgs.append(img_msg)
resp1 = classify_client(req)
class_resp= np.asarray(resp1.out.data)
cont3=0
class_labels=[]
for cla in class_resp:
if cont3==3:
print '-----------------'
cont3=0
print (class_names [(int)(cla)])
class_labels.append(class_names [(int)(cla)])
cont3+=1
return class_resp
def shelf_line_up(target_distance=0.5,target_link='Object0_Shelf_low'):
###Face towards Targetlink and get target distance close
try:
obj_pose,_ = listener.lookupTransform('map',target_link,rospy.Time(0))
print (obj_pose)
new_pose= obj_pose
new_pose[1]+=-target_distance
except(tf.LookupException):
print ('no tf found')
return False
arm.set_named_target('go')
arm.go()
succ=move_base( new_pose[0],new_pose[1], 0.5*np.pi)
return succ
##### Define state INITIAL #####
#Estado inicial de takeshi, neutral
class Initial(smach.State):
def __init__(self):
smach.State.__init__(self,outcomes=['succ','failed','tries'],input_keys=['global_counter'])
self.tries=0
def execute(self,userdata):
publish_scene()
rospy.loginfo('STATE : robot neutral pose and go to inital pose of task 2')
self.tries+=1
clear_octo_client()
close_gripper()
scene.remove_world_object()
#Takeshi neutral
arm.set_named_target('go')
arm.go()
head.set_named_target('neutral')
succ = head.go()
move_base(2.5,1,0.5*np.pi)
head_val=head.get_current_joint_values()
head_val[0]=np.deg2rad(0)
head_val[1]=np.deg2rad(-30)
image_data , points_data=rgbd.get_image(),rgbd.get_points()
succ=head.go(head_val)
if succ:
return 'succ'
else:
return 'failed'
class Scan_floor(smach.State):### check next state's goal
def __init__(self):
smach.State.__init__(self,outcomes=['succ','clear','failed','tries'] ,input_keys=['clear_flag'],output_keys=['clear_flag'])
self.tries=0
def execute(self,userdata):
if userdata.clear_flag:
print('clear floor table 1 flag', userdata.clear_flag)
return 'clear'
global class_resp ,closest_centroid_height,closest_centroid_index ,target_tf
rospy.loginfo('State : Scan Floor ')
#move_base(0.5+0.1*self.tries,0.15+0.1*self.tries,(0.4+0.1*self.tries)*np.pi)
gaze_point(2.8,2.15 ,0.01)
cents,xyz, images=plane_seg_square_imgs(lower=10)
if len (cents) ==0:
print ('no objects found by segmentator ')
return 'failed'
scene.remove_world_object()
closest_centroid_height,closest_centroid_index=static_tf_publish(cents)
print ("closest_centroid_height,closest_centroid_index",closest_centroid_height,closest_centroid_index)
cents_to_sceneobjs(cents)
publish_scene()
#cents,xyz, images=seg_square_imgs(plt_images=True)
#req=classify_client.request_class()
for i in range(5):
arm.set_named_target('go')
arm.go()
head.set_named_target('neutral')
head.go()
wb=whole_body.get_current_joint_values()
wb[0]=3.7
wb[1]=2.5
wb[2]=np.pi
#wb[3]+=0.5
print i
#wb[4:]=arm_grasp_table[1:]
try:
plan = whole_body.plan(wb)
succ=whole_body.go(wb)
except:
print('something happened')
succ= False
if succ:
break
#move_base(0.7+0.1*self.tries,0.6+0.1*self.tries,0.5*np.pi)
if succ:return 'succ'
if self.tries >=5:
self.tries= 0
return 'tries'
#if closest_centroid_height <= 0.001:return 'above'
else:return 'failed'
class Scan_shelf(smach.State):
def __init__(self):
smach.State.__init__(self,outcomes=['succ','failed','tries'])
self.tries=0
def execute(self,userdata):
global closest_centroid_index , message_read
self.tries+=1
rospy.loginfo('State : Scan Shelves ')
publish_scene()
arm.set_named_target('go')
arm.go()
move_base(2.5-0.1*self.tries,3.7+0.05*self.tries,np.pi)
av=arm.get_current_joint_values()
av[0]=0.1*self.tries
av[1]=-0.12
arm.go(av)
gaze_point(2.5,4.7,0.3)
print ('request message is',message_read.split(' ')[0] , 'try num ',self.tries)
cents, xyz, imgs= seg_square_imgs(reg_lx=30, reg_hx=500, lower=500,higher=6000,plt_images=True)
if len(cents)==0:return'failed'
#closest_centroid_height,closest_centroid_index=static_tf_publish(cents)
class_resp=classify_images(imgs)
requested_centroid_index= messg_class_name_idx( message_read.split(' ')[0] ,class_resp )
print (requested_centroid_index,'#####################################################################')
if requested_centroid_index ==False:
if self.tries==5:
closest_centroid_height,closest_centroid_index=static_tf_publish(cents)
print("target closest cent index" ,cents[closest_centroid_index,:])
static_tf_publish(cents[closest_centroid_index:,:])
self.tries=0
return'tries'
else:
return'failed'
else:
print("target cent" ,cents[requested_centroid_index])
static_tf_publish(cents[requested_centroid_index])
return 'succ'
class Pre_grasp_shelf(smach.State):###get a convenient pre grasp pose
def __init__(self):
smach.State.__init__(self,outcomes=['succ','failed','tries'])
self.tries=0
def execute(self,userdata):
global target_tf
rospy.loginfo('State : PRE_GRASP_SHELF')
pose, quat = listener.lookupTransform('map','base_link',rospy.Time(0))
print ('base', pose, tf.transformations.euler_from_quaternion(quat)[2])
publish_scene()
target_tf= 'Object_0_Shelf_low' ####ONly target tf
head.set_named_target('neutral')
head.go()
try:
listener.lookupTransform('map',target_tf,rospy.Time(0))
except:
target_tf= 'Object_0_Shelf_high'
try:
listener.lookupTransform('map',target_tf,rospy.Time(0))
except:
print ('no tf found')
return 'failed'
shelf_line_up(0.81,target_tf) ############### PLAY WITH THIS NUMBER
print ('shelf_line_up')
succ=arm.set_named_target('neutral')
open_gripper()
pose, quat = listener.lookupTransform('map','base_link',rospy.Time(0))
print ('base', pose, tf.transformations.euler_from_quaternion(quat)[2])
print ('whole_body', whole_body.get_current_joint_values()[:3])
#pose, quat = listener.lookupTransform('hand_palm_link',target_tf,rospy.Time(0))
#print ('hand to closest target', pose, tf.transformations.euler_from_quaternion(quat)[2])
#arm.go()
#if self.tries <=5:move_abs(0,0,-10,0.051)
arm.set_joint_value_target(arm_grasp_table)
succ=arm.go()
#pose,quat=listener.lookupTransform('map','base_link',rospy.Time(0))
pose, quat = listener.lookupTransform('hand_palm_link',target_tf,rospy.Time(0))
print ('hand to target transform' ,pose, euler_from_quaternion(quat))
#move_abs(0.0,0.051,0, 0.5*np.abs(pose[0]/.1))
#rospy.sleep(0.5)
if succ:
return 'succ'
self.tries+=1
if self.tries==3:
self.tries=0
return'tries'
else:
return 'failed'
class Grasp_shelf(smach.State):
def __init__(self):
smach.State.__init__(self,outcomes=['succ','failed','tries'])
self.tries=0
def execute(self,userdata):
rospy.loginfo('State : GRASP_shelf')
pose, quat = listener.lookupTransform('hand_palm_link',target_tf,rospy.Time(0))
open_gripper()
av= arm.get_current_joint_values()
if target_tf[-3:]=='low' :av[0]=0.28
if target_tf[-4:]=='high':av[0]=0.57
arm.go(av)
while pose[2] >= 0.091:
if pose[1] > 0.02:
print ('drift correct -')
move_abs(0.0,-0.031,-5, 0.051) #GRADOS! WTF , DOCKER SEEMS TO WORK THAT WAY
elif pose[1] < -0.02:
print ('drift correct +')
move_abs(0.00, 0.031,5, 0.051) #GRADOS! WTF ,
else:
print ('getting close')
move_abs(0.04,0,0,0.051)
pose, quat = listener.lookupTransform('hand_palm_link',target_tf,rospy.Time(0))
#rospy.sleep(0.1)
rospy.sleep(0.05)
close_gripper()
#checkgrasp
#av= arm.get_current_joint_values()
#av[0]+=0.1
#arm.set_joint_value_target(av)
#succ=arm.go(av)