-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathpick_and_place_state_machine2
859 lines (738 loc) · 44 KB
/
pick_and_place_state_machine2
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
#!/usr/bin/env python
import rospy
from math import pow, atan2, sqrt
from tf.transformations import *
import smach
import smach_ros
from smach_ros import SimpleActionState
from smach_ros import ServiceState
import threading
# Navigation
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Twist
# Manipulator
from geometry_msgs.msg import Pose
from open_manipulator_msgs.msg import JointPosition
from open_manipulator_msgs.msg import KinematicsPose
from open_manipulator_msgs.srv import SetJointPosition
from open_manipulator_msgs.srv import SetKinematicsPose
from open_manipulator_msgs.srv import GetJointPosition
from open_manipulator_msgs.srv import GetKinematicsPose
# AR Markers
from ar_track_alvar_msgs.msg import AlvarMarker
from ar_track_alvar_msgs.msg import AlvarMarkers
from geometry_msgs.msg import PoseArray, Pose
from detection_clustering import DetectionClustering
import time
from tf.transformations import euler_from_quaternion, quaternion_from_euler
from darknet_ros_msgs.msg import BoundingBoxes
from darknet_ros_msgs.msg import BoundingBox
import tf
class getPoseOfTheObject(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'aborted'],
output_keys=['output_object_pose'])
self.detected = {}
self.detection_names = rospy.get_param('/darknet_ros/yolo_model/detection_classes/names')
#print(self.detection_names)
#self.namespace = rospy.get_param("~robot_name")
#self.marker_pose_sub = rospy.Subscriber(self.namespace + '/ar_pose_marker', AlvarMarkers, self.arMarkerMsgCallback)
self.object_pose_sub = rospy.Subscriber('/cluster_decomposer/centroid_pose_array', PoseArray, self.collect)
self.listener = tf.TransformListener()
#self.OFFSET_FOR_GOAL_HEIGHT = 0.150
def collect(self, msg):
for i, pose in enumerate(msg.poses):
if pose != Pose():
try:
#(trans1,rot1) = self.listener.lookupTransform('map', 'yolo_output'+str(i), rospy.Time(0))
(trans,rot) = self.listener.lookupTransform('om_with_tb3/camera_link', 'yolo_output'+str(i), rospy.Time(0))
#print 'Found a {} at {} num{} TF {} '.format(key, val, i, trans)
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
rospy.logwarn('there is no tf ')
pos = pose.position
val = [round(pos.x,2), round(pos.y,2), round(pos.z,2), round(trans[0],2), round(trans[1],2) , round(trans[2],2)]
key = self.detection_names[i]
self.update_key(key, val)
def update_key(self, key, val):
if self.detected.has_key(key):
self.detected[key].append(val)
else:
self.detected[key] = [val]
def execute(self, userdata):
time.sleep(0.5)
if len(self.detected) == 0:
rospy.logwarn('there is no object')
return 'aborted'
elif self.detected.has_key("bottle"):
object_pose = Pose()
object_pose.position.x = self.detected["bottle"][-1][0]
object_pose.position.y = self.detected["bottle"][-1][1]
object_pose.position.z = self.detected["bottle"][-1][2]
object_pose.orientation.x = 0
object_pose.orientation.y = 0
object_pose.orientation.z = 0
object_pose.orientation.w = 1
userdata.output_object_pose = object_pose
return 'succeeded'
else:
rospy.logwarn('there is no bottle')
return 'aborted'
self.object_pose_sub
class getPoseOfTheObjectAtBaseLink(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'aborted'],
output_keys=['output_object_pose'])
self.detected = {}
self.detection_names = rospy.get_param('/darknet_ros/yolo_model/detection_classes/names')
#print(self.detection_names)
#self.namespace = rospy.get_param("~robot_name")
#self.marker_pose_sub = rospy.Subscriber(self.namespace + '/ar_pose_marker', AlvarMarkers, self.arMarkerMsgCallback)
self.object_pose_sub = rospy.Subscriber('/cluster_decomposer/centroid_pose_array', PoseArray, self.collect)
self.listener = tf.TransformListener()
#self.OFFSET_FOR_GOAL_HEIGHT = 0.150
def collect(self, msg):
for i, pose in enumerate(msg.poses):
if pose != Pose():
try:
(trans,rot) = self.listener.lookupTransform('om_with_tb3/base_link', 'yolo_output'+str(i), rospy.Time(0))
#(trans2,rot) = self.listener.lookupTransform('om_with_tb3/base_link', 'om_with_tb3/end_effector_link', rospy.Time(0))
pos = pose.position
val = [round(pos.x,2), round(pos.y,2), round(pos.z,2), round(trans[0],2), round(trans[1],2) , round(trans[2],2)]
key = self.detection_names[i]
#print 'Found a {} at {} num{} TF {} '.format(key, val, i, trans)
self.update_key(key, val)
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
rospy.logwarn('there is exception')
def update_key(self, key, val):
if self.detected.has_key(key):
self.detected[key].append(val)
else:
self.detected[key] = [val]
def execute(self, userdata):
time.sleep(0.5)
if len(self.detected) == 0:
rospy.logwarn('there is no object')
return 'aborted'
elif self.detected.has_key("bottle"):
object_pose = Pose()
object_pose.position.x = self.detected["bottle"][-1][3]
object_pose.position.y = self.detected["bottle"][-1][4]
object_pose.position.z = self.detected["bottle"][-1][5]
object_pose.orientation.x = 0
object_pose.orientation.y = 0
object_pose.orientation.z = 0
object_pose.orientation.w = 1
userdata.output_object_pose = object_pose
return 'succeeded'
else:
rospy.logwarn('there is no bottle')
return 'aborted'
self.object_pose_sub
class getPoseOfTheBox(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'aborted'],
output_keys=['output_object_pose'])
self.namespace = rospy.get_param("~robot_name")
self.marker_pose_sub = rospy.Subscriber(self.namespace + '/ar_pose_marker', AlvarMarkers, self.arMarkerMsgCallback)
self.OFFSET_FOR_STRETCH = 0.070
self.OFFSET_FOR_GOAL_HEIGHT = 0.200
def arMarkerMsgCallback(self, ar_marker_pose_msg):
if len(ar_marker_pose_msg.markers) == 0:
self.ar_marker_pose = False
else:
self.ar_marker_pose = AlvarMarker()
self.ar_marker_pose = ar_marker_pose_msg.markers[0]
def execute(self, userdata):
if self.ar_marker_pose == False:
rospy.logwarn('Failed to get pose of the marker')
return 'aborted'
else:
object_pose = Pose()
object_pose.position = self.ar_marker_pose.pose.pose.position
object_pose.position.x += self.OFFSET_FOR_STRETCH
object_pose.position.y = 0.0
object_pose.position.z += self.OFFSET_FOR_GOAL_HEIGHT
dist = math.sqrt((self.ar_marker_pose.pose.pose.position.x * self.ar_marker_pose.pose.pose.position.x) +
(self.ar_marker_pose.pose.pose.position.y * self.ar_marker_pose.pose.pose.position.y))
if self.ar_marker_pose.pose.pose.position.y > 0:
yaw = math.acos(self.ar_marker_pose.pose.pose.position.x / dist)
else:
yaw = (-1) * math.acos(self.ar_marker_pose.pose.pose.position.x / dist)
roll = 0.0
pitch = 0.0
cy = math.cos(yaw * 0.5)
sy = math.sin(yaw * 0.5)
cr = math.cos(roll * 0.5)
sr = math.sin(roll * 0.5)
cp = math.cos(pitch * 0.5)
sp = math.sin(pitch * 0.5)
object_pose.orientation.w = cy * cr * cp + sy * sr * sp
object_pose.orientation.x = cy * sr * cp - sy * cr * sp
object_pose.orientation.y = cy * cr * sp + sy * sr * cp
object_pose.orientation.z = sy * cr * cp - cy * sr * sp
userdata.output_object_pose = object_pose
rospy.loginfo('Succeeded to get pose of the object')
return 'succeeded'
self.marker_pose_sub
class getCloserToGoal(smach.State):
def __init__(self):
smach.State.__init__(self, outcomes=['succeeded', 'failed'])
self.detected = {}
self.namespace = rospy.get_param("~robot_name")
#self.detection_names = rospy.get_param('/darknet_ros/yolo_model/detection_classes/names')
self.darknet_pose_sub = rospy.Subscriber('/darknet_ros/bounding_boxes', BoundingBoxes, self.darknetBoundingBoxesCallback)
self.odom_sub = rospy.Subscriber(self.namespace + '/odom', Odometry, self.odomMsgCallback)
self.cmd_vel_pub = rospy.Publisher(self.namespace + '/cmd_vel', Twist, queue_size=10)
self.tb3_odom = Odometry()
rospy.loginfo('Succeeded to get pose of the object')
self.cmd_vel = Twist()
self.priv_dist = 0.0
self.priv_heading = 0.0
def darknetBoundingBoxesCallback(self, darknet_pose_msg):
#rospy.loginfo('Darknet get msg %d , %.2f', len(darknet_pose_msg.bounding_boxes), darknet_pose_msg.bounding_boxes[0].Z)
for i, bounding_boxes in enumerate(darknet_pose_msg.bounding_boxes):
if bounding_boxes != BoundingBox():
val = [bounding_boxes.X, bounding_boxes.Y, bounding_boxes.Z, rospy.Time.now()]
key = bounding_boxes.Class
#print 'Found a {} at {}'.format(key, val)
self.update_key(key, val)
def update_key(self, key, val):
if self.detected.has_key(key):
self.detected[key].append(val)
else:
self.detected[key] = [val]
def odomMsgCallback(self, odom_msg):
self.tb3_odom = odom_msg
def getDistanceFromRobot(self, goal):
return goal.pose.pose.position.x
def getAngleBtwRobotAndMarker(self, goal):
return math.atan2(goal.pose.pose.position.y, goal.pose.pose.position.x)
def moveTB3(self, mode, value):
self.cmd_vel.linear.x = -0.001
self.cmd_vel.linear.y = 0.0
self.cmd_vel.linear.z = 0.0
self.cmd_vel.angular.x = 0.0
self.cmd_vel.angular.y = 0.0
self.cmd_vel.angular.z = 0.0
if mode == 'left':
self.cmd_vel.angular.z = value
elif mode == 'right':
self.cmd_vel.angular.z = -value
elif mode == 'forward':
self.cmd_vel.linear.x = value
elif mode == 'backward':
self.cmd_vel.linear.x = -value
#rospy.loginfo('%s , linear.x %.2f, angular.z %.2f',mode, self.cmd_vel.linear.x, self.cmd_vel.angular.z)
self.cmd_vel_pub.publish(self.cmd_vel)
def execute(self, userdata):
return 'succeeded'
while 1:
#if (len(self.detected) == 0) or (self.detected.has_key("bottle") == False):
if self.detected.has_key("bottle") == False :
rospy.loginfo('Failed to get pose of bottle')
self.moveTB3('left', 0.01 )
continue
dist = self.detected["bottle"][-1][2]
cam_x = self.detected["bottle"][-1][0]
heading = round((1920-526)/2 - cam_x)
rospy.loginfo('data dist %.2f, cam_x %d ,heading %d ', dist, cam_x, heading)
heading_limit = 30
dist_limit = 0.2
if (abs( heading ) < heading_limit) and (dist < dist_limit) :
self.moveTB3('stop', 0.00)
return 'succeeded'
if heading > heading_limit :
self.moveTB3('left', 0.01)
elif heading < -heading_limit :
self.moveTB3('right', 0.01)
elif dist > dist_limit :
self.moveTB3('forward', 0.1)
self.priv_dist = dist
self.priv_heading = heading
def main():
rospy.init_node('pick_and_place_state_machine1')
namespace = rospy.get_param("~robot_name")
planning_group = rospy.get_param("~planning_group")
# Create the sub SMACH state machine
task_center = smach.StateMachine(outcomes=['succeeded','aborted','preempted'])
# Open the container
with task_center:
def get_location_pose_request_cb(userdata, goal):
the_location_of_the_point = MoveBaseGoal()
the_location_of_the_point.target_pose.header.frame_id = "map"
the_location_of_the_point.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_point.target_pose.pose.position.x = userdata.input_object_pose.position.x
the_location_of_the_point.target_pose.pose.position.y = userdata.input_object_pose.position.y - 0.7
the_location_of_the_point.target_pose.pose.position.z = 0
quat = quaternion_from_euler(0, 0, 1.5708)
the_location_of_the_point.target_pose.pose.orientation.x = quat[0]
the_location_of_the_point.target_pose.pose.orientation.y = quat[1]
the_location_of_the_point.target_pose.pose.orientation.z = quat[2]
the_location_of_the_point.target_pose.pose.orientation.w = quat[3]
rospy.loginfo('location pose : %.2f, %.2f, %.2f ( x:%.2f, y:%.2f, z:%.2f, w:%.2f )',\
the_location_of_the_point.target_pose.pose.position.x,\
the_location_of_the_point.target_pose.pose.position.y,\
the_location_of_the_point.target_pose.pose.position.z,\
the_location_of_the_point.target_pose.pose.orientation.x,\
the_location_of_the_point.target_pose.pose.orientation.y,\
the_location_of_the_point.target_pose.pose.orientation.z,\
the_location_of_the_point.target_pose.pose.orientation.w )
return the_location_of_the_point
task_center.userdata.object_pose = Pose()
task_center.userdata.object_pose_atcamera = Pose()
'''
smach.StateMachine.add('GET_POSE_OF_THE_OBJECT', getPoseOfTheObject(),
transitions={'succeeded':'GO_TO_THE_OBJECT',
#transitions={'succeeded':'GET_POSE_OF_THE_OBJECT',
'aborted':'GET_POSE_OF_THE_OBJECT'},
remapping={'output_object_pose':'object_pose'})
smach.StateMachine.add('GO_TO_THE_OBJECT',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal_cb=get_location_pose_request_cb,
input_keys=['input_object_pose']),
transitions={'succeeded':'GET_CLOSER_TO_OBJECT'},
remapping={'input_object_pose':'object_pose'})
'''
smach.StateMachine.add('GET_CLOSER_TO_OBJECT', getCloserToGoal(),
transitions={'succeeded':'PICK',
'failed':'PICK'})
#'failed':'aborted'})
# Add states to the container
'''
smach.StateMachine.add('GO_TO_THE_OBJECT',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
request_cb=goal_pose_request_cb,
goal='goal_pose'),
transitions={'succeeded':'aborted'})
pick_center.userdata.align_arm_with_object_tolerance = 0.01
smach.StateMachine.add('GO_TO_THE_OBJECT',
ServiceState(planning_group + '/moveit/set_kinematics_pose',
SetKinematicsPose,
request_cb=eef_pose_request_cb,
response_cb=align_arm_with_object_response_cb,
input_keys=['input_planning_group',
'input_pose',
'input_tolerance']),
transitions={'succeeded':'CLOSE_TO_OBJECT',
'aborted':'ALIGN_ARM_WITH_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_pose':'object_pose',
'input_tolerance':'align_arm_with_object_tolerance'})
'''
'''
smach.StateMachine.add('GO_TO_THE_OBJECT',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal='object_pose'),
transitions={'succeeded':'aborted'})
'''
the_location_of_the_left_room = MoveBaseGoal()
the_location_of_the_left_room.target_pose.header.frame_id = "map"
the_location_of_the_left_room.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_left_room.target_pose.pose.position.x = -2.0
the_location_of_the_left_room.target_pose.pose.position.y = 1.0
the_location_of_the_left_room.target_pose.pose.position.z = 0.0
the_location_of_the_left_room.target_pose.pose.orientation.w = 0.705
the_location_of_the_left_room.target_pose.pose.orientation.x = 0.0
the_location_of_the_left_room.target_pose.pose.orientation.y = 0.0
the_location_of_the_left_room.target_pose.pose.orientation.z = 0.705
the_location_of_the_object = MoveBaseGoal()
the_location_of_the_object.target_pose.header.frame_id = "map"
the_location_of_the_object.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_object.target_pose.pose.position.x = -1.393
the_location_of_the_object.target_pose.pose.position.y = 3.500
the_location_of_the_object.target_pose.pose.position.z = 0.0
the_location_of_the_object.target_pose.pose.orientation.w = 0.705
the_location_of_the_object.target_pose.pose.orientation.x = 0.0
the_location_of_the_object.target_pose.pose.orientation.y = 0.0
the_location_of_the_object.target_pose.pose.orientation.z = 0.705
# Add states to the container
'''
smach.StateMachine.add('GO_TO_THE_LEFT_ROOM',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal=the_location_of_the_left_room),
transitions={'succeeded':'GO_TO_THE_OBJECT'})
smach.StateMachine.add('GO_TO_THE_OBJECT',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal=the_location_of_the_object),
transitions={'succeeded':'GET_CLOSER_TO_OBJECT'})
'''
the_location_of_the_point = MoveBaseGoal()
the_location_of_the_point.target_pose.header.frame_id = "map"
the_location_of_the_point.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_point.target_pose.pose.position.x = -2.0
the_location_of_the_point.target_pose.pose.position.y = 1.0
the_location_of_the_point.target_pose.pose.position.z = 0.0
the_location_of_the_point.target_pose.pose.orientation.w = 1.0
the_location_of_the_point.target_pose.pose.orientation.x = 0.0
the_location_of_the_point.target_pose.pose.orientation.y = 0.0
the_location_of_the_point.target_pose.pose.orientation.z = 0.0
the_location_of_the_right_room = MoveBaseGoal()
the_location_of_the_right_room.target_pose.header.frame_id = "map"
the_location_of_the_right_room.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_right_room.target_pose.pose.position.x = 2.0
the_location_of_the_right_room.target_pose.pose.position.y = 1.0
the_location_of_the_right_room.target_pose.pose.position.z = 0.0
the_location_of_the_right_room.target_pose.pose.orientation.w = 0.705
the_location_of_the_right_room.target_pose.pose.orientation.x = 0.0
the_location_of_the_right_room.target_pose.pose.orientation.y = 0.0
the_location_of_the_right_room.target_pose.pose.orientation.z = 0.705
the_location_of_the_box = MoveBaseGoal()
the_location_of_the_box.target_pose.header.frame_id = "map"
the_location_of_the_box.target_pose.header.stamp = rospy.Time.now()
the_location_of_the_box.target_pose.pose.position.x = 0.766
the_location_of_the_box.target_pose.pose.position.y = 3.670
the_location_of_the_box.target_pose.pose.position.z = 0.0
the_location_of_the_box.target_pose.pose.orientation.w = 0.705
the_location_of_the_box.target_pose.pose.orientation.x = 0.0
the_location_of_the_box.target_pose.pose.orientation.y = 0.0
the_location_of_the_box.target_pose.pose.orientation.z = 0.705
smach.StateMachine.add('GO_TO_THE_TURN_AROUND_POINT',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal=the_location_of_the_point),
transitions={'succeeded':'GO_TO_THE_RIGHT_ROOM'})
smach.StateMachine.add('GO_TO_THE_RIGHT_ROOM',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal=the_location_of_the_right_room),
transitions={'succeeded':'GO_TO_THE_BOX'})
smach.StateMachine.add('GO_TO_THE_BOX',
SimpleActionState(namespace + "/move_base",
MoveBaseAction,
goal=the_location_of_the_box),
transitions={'succeeded':'GET_CLOSER_TO_BOX'})
smach.StateMachine.add('GET_CLOSER_TO_BOX', getCloserToGoal(),
transitions={'succeeded':'PLACE',
'failed':'aborted'})
# Create the sub SMACH state machine
pick_center = smach.StateMachine(outcomes=['succeeded','aborted','preempted'])
with pick_center:
pick_center.userdata.planning_group = planning_group
def joint_position_request_cb(userdata, request):
joint = JointPosition()
joint.position = userdata.input_position
joint.max_velocity_scaling_factor = 1.0
joint.max_accelerations_scaling_factor = 1.0
request.planning_group = userdata.input_planning_group
request.joint_position = joint
return request
def joint_position_response_cb(userdata, response):
if response.is_planned == False:
return 'aborted'
else:
rospy.sleep(3.)
return 'succeeded'
def eef_pose_request_cb(userdata, request):
eef = KinematicsPose()
eef.pose = userdata.input_pose
#rospy.loginfo('eef.position.x : %f', eef.pose.position.x)
#rospy.loginfo('eef.position.y : %f', eef.pose.position.y)
#rospy.loginfo('eef.position.z : %f', eef.pose.position.z)
eef.pose.position.z =0.1
rospy.loginfo('eef.position: %.2f , %.2f, %.2f ', eef.pose.position.x, eef.pose.position.y, eef.pose.position.z )
eef.max_velocity_scaling_factor = 1.0
eef.max_accelerations_scaling_factor = 1.0
eef.tolerance = userdata.input_tolerance
request.planning_group = userdata.input_planning_group
request.kinematics_pose = eef
return request
def eef_get_pose_request_cb(userdata, request):
request.planning_group = userdata.input_planning_group
return request
def eef_get_pose_response_cb(userdata, response):
rospy.loginfo("eef_get_pose_response_cb %.2f, %.2f, %.2f ", \
response.kinematics_pose.pose.position.x, response.kinematics_pose.pose.position.y, response.kinematics_pose.pose.position.z)
arm_pose = KinematicsPose()
arm_pose.pose.position.x = response.kinematics_pose.pose.position.x
arm_pose.pose.position.y = response.kinematics_pose.pose.position.y
arm_pose.pose.position.z = response.kinematics_pose.pose.position.z
userdata.output_arm_pose = arm_pose
return 'succeeded'
def eef_get_pose1_response_cb(userdata, response):
rospy.loginfo("eef_get_pose_response_cb %.2f, %.2f, %.2f ", \
response.kinematics_pose.pose.position.x, response.kinematics_pose.pose.position.y, response.kinematics_pose.pose.position.z)
arm_pose = KinematicsPose()
OFFSET_FOR_STRETCH = 0.030
arm_pose.pose.position.x = response.kinematics_pose.pose.position.x - OFFSET_FOR_STRETCH
arm_pose.pose.position.y = response.kinematics_pose.pose.position.y
arm_pose.pose.position.z = response.kinematics_pose.pose.position.z
userdata.output_arm_pose = arm_pose
return 'succeeded'
def align_arm_with_object_response_cb(userdata, response):
if response.is_planned == False:
pick_center.userdata.align_arm_with_object_tolerance += 0.005
rospy.logwarn('Set more tolerance[%f]', pick_center.userdata.align_arm_with_object_tolerance)
return 'aborted'
else:
OFFSET_FOR_STRETCH = 0.030
pick_center.userdata.object_pose.position.x += OFFSET_FOR_STRETCH
rospy.sleep(3.)
return 'succeeded'
def close_to_object_response_cb(userdata, response):
if response.is_planned == False:
pick_center.userdata.close_to_object_tolerance += 0.005
rospy.logwarn('Set more tolerance[%f]', pick_center.userdata.close_to_object_tolerance)
return 'aborted'
else:
OFFSET_FOR_OBJECT_HEIGHT = 0.020
pick_center.userdata.object_pose.position.z += OFFSET_FOR_OBJECT_HEIGHT
rospy.sleep(3.)
return 'succeeded'
def pick_up_object_response_cb(userdata, response):
if response.is_planned == False:
pick_center.userdata.pick_up_object_tolerance += 0.005
rospy.logwarn('Set more tolerance[%f]', pick_center.userdata.pick_up_object_tolerance)
return 'aborted'
else:
rospy.sleep(3.)
return 'succeeded'
def gripper_request_cb(userdata, request):
joint = JointPosition()
joint.position = userdata.input_gripper
joint.max_velocity_scaling_factor = 1.0
joint.max_accelerations_scaling_factor = 1.0
request.planning_group = userdata.input_planning_group
request.joint_position = joint
return request
def gripper_response_cb(userdata, response):
rospy.sleep(1.)
return 'succeeded'
pick_center.userdata.object_pose = Pose()
smach.StateMachine.add('GET_POSE_OF_THE_OBJECT', getPoseOfTheObjectAtBaseLink(),
transitions={'succeeded':'SET_INIT_POSITION',
#transitions={'succeeded':'ALIGN_ARM_WITH_OBJECT',
#transitions={'succeeded':'GET_POSE_OF_THE_OBJECT',
'aborted':'GET_POSE_OF_THE_OBJECT'},
remapping={'output_object_pose':'object_pose'})
pick_center.userdata.init_position = [0.0, -0.65, 1.20, -0.54]
smach.StateMachine.add('SET_INIT_POSITION',
ServiceState(planning_group + '/moveit/set_joint_position',
SetJointPosition,
request_cb=joint_position_request_cb,
response_cb=joint_position_response_cb,
input_keys=['input_planning_group',
'input_position']),
transitions={'succeeded':'OPEN_GRIPPER'},
remapping={'input_planning_group':'planning_group',
'input_position':'init_position'})
pick_center.userdata.open_gripper = [0.15]
smach.StateMachine.add('OPEN_GRIPPER',
ServiceState(namespace + '/gripper',
SetJointPosition,
request_cb=gripper_request_cb,
response_cb=gripper_response_cb,
input_keys=['input_planning_group',
'input_gripper']),
transitions={'succeeded':'ALIGN_ARM_WITH_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_gripper':'open_gripper'})
#defualt end point
#0.04, 0.00, 0.22
'''
pick_center.userdata.arm_kinematics_pose = KinematicsPose()
smach.StateMachine.add('GET_KINEMATICS_POSITION',
ServiceState(planning_group + '/moveit/get_kinematics_pose',
GetKinematicsPose,
request_cb=eef_get_pose_request_cb,
response_cb=eef_get_pose_response_cb,
input_keys=['input_planning_group'],
output_keys=['output_arm_pose']),
transitions={'succeeded':'GET_KINEMATICS_POSITION',
'aborted':'GET_KINEMATICS_POSITION'},
remapping={'input_planning_group':'planning_group',
'output_arm_pose':'arm_kinematics_pose'})
'''
pick_center.userdata.align_arm_with_object_tolerance = 0.01
smach.StateMachine.add('ALIGN_ARM_WITH_OBJECT',
ServiceState(planning_group + '/moveit/set_kinematics_pose',
SetKinematicsPose,
request_cb=eef_pose_request_cb,
response_cb=align_arm_with_object_response_cb,
input_keys=['input_planning_group',
'input_pose',
'input_tolerance']),
transitions={'succeeded':'CLOSE_TO_OBJECT',
'aborted':'ALIGN_ARM_WITH_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_pose':'object_pose',
'input_tolerance':'align_arm_with_object_tolerance'})
pick_center.userdata.close_to_object_tolerance = 0.01
smach.StateMachine.add('CLOSE_TO_OBJECT',
ServiceState(planning_group + '/moveit/set_kinematics_pose',
SetKinematicsPose,
request_cb=eef_pose_request_cb,
response_cb=close_to_object_response_cb,
input_keys=['input_planning_group',
'input_pose',
'input_tolerance']),
transitions={'succeeded':'GRIP_OBJECT',
'aborted':'CLOSE_TO_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_pose':'object_pose',
'input_tolerance':'close_to_object_tolerance'})
pick_center.userdata.close_gripper = [0.0]
smach.StateMachine.add('GRIP_OBJECT',
ServiceState(namespace + '/gripper',
SetJointPosition,
request_cb=gripper_request_cb,
response_cb=gripper_response_cb,
input_keys=['input_planning_group',
'input_gripper']),
transitions={'succeeded':'PICK_UP_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_gripper':'close_gripper'})
pick_center.userdata.pick_up_object_tolerance = 0.01
smach.StateMachine.add('PICK_UP_OBJECT',
ServiceState(planning_group + '/moveit/set_kinematics_pose',
SetKinematicsPose,
request_cb=eef_pose_request_cb,
response_cb=pick_up_object_response_cb,
input_keys=['input_planning_group',
'input_pose',
'input_tolerance']),
transitions={'succeeded':'SET_HOLDING_POSITION',
'aborted':'PICK_UP_OBJECT'},
remapping={'input_planning_group':'planning_group',
'input_pose':'object_pose',
'input_tolerance':'pick_up_object_tolerance'})
pick_center.userdata.holding_position = [0.0, -1.5707, 1.37, -0.20]
smach.StateMachine.add('SET_HOLDING_POSITION',
ServiceState(planning_group + '/moveit/set_joint_position',
SetJointPosition,
request_cb=joint_position_request_cb,
response_cb=joint_position_response_cb,
input_keys=['input_planning_group',
'input_position']),
transitions={'succeeded':'succeeded'},
remapping={'input_planning_group':'planning_group',
'input_position':'holding_position'})
smach.StateMachine.add('PICK', pick_center,
transitions={'succeeded':'GO_TO_THE_TURN_AROUND_POINT', 'aborted':'aborted'})
# Create the sub SMACH state machine
place_center = smach.StateMachine(outcomes=['succeeded','aborted','preempted'])
with place_center:
place_center.userdata.planning_group = planning_group
def joint_position_request_cb(userdata, request):
joint = JointPosition()
joint.position = userdata.input_position
joint.max_velocity_scaling_factor = 1.0
joint.max_accelerations_scaling_factor = 1.0
request.planning_group = userdata.input_planning_group
request.joint_position = joint
return request
def joint_position_response_cb(userdata, response):
if response.is_planned == False:
return 'aborted'
else:
rospy.sleep(3.)
return 'succeeded'
def eef_pose_request_cb(userdata, request):
eef = KinematicsPose()
eef.pose = userdata.input_pose
rospy.loginfo('eef.position.x : %f', eef.pose.position.x)
rospy.loginfo('eef.position.y : %f', eef.pose.position.y)
rospy.loginfo('eef.position.z : %f', eef.pose.position.z)
eef.max_velocity_scaling_factor = 1.0
eef.max_accelerations_scaling_factor = 1.0
eef.tolerance = userdata.input_tolerance
request.planning_group = userdata.input_planning_group
request.kinematics_pose = eef
return request
def close_to_box_response_cb(userdata, response):
if response.is_planned == False:
pick_center.userdata.close_to_box_tolerance += 0.005
rospy.logwarn('Set more tolerance[%f]', pick_center.userdata.close_to_box_tolerance)
return 'aborted'
else:
rospy.sleep(3.)
return 'succeeded'
def gripper_request_cb(userdata, request):
joint = JointPosition()
joint.position = userdata.input_gripper
joint.max_velocity_scaling_factor = 1.0
joint.max_accelerations_scaling_factor = 1.0
request.planning_group = userdata.input_planning_group
request.joint_position = joint
return request
def gripper_response_cb(userdata, response):
rospy.sleep(1.)
return 'succeeded'
place_center.userdata.ready_position = [0.0, -1.05, 0.35, 0.70]
smach.StateMachine.add('SET_INIT_POSITION',
ServiceState(planning_group + '/moveit/set_joint_position',
SetJointPosition,
request_cb=joint_position_request_cb,
response_cb=joint_position_response_cb,
input_keys=['input_planning_group',
'input_position']),
transitions={'succeeded':'GET_POSE_OF_THE_BOX'},
remapping={'input_planning_group':'planning_group',
'input_position':'ready_position'})
smach.StateMachine.add('GET_INIT_POSITION',
ServiceState(planning_group + '/moveit/set_joint_position',
SetJointPosition,
request_cb=joint_position_request_cb,
response_cb=joint_position_response_cb,
input_keys=['input_planning_group',
'input_position']),
transitions={'succeeded':'GET_POSE_OF_THE_BOX'},
remapping={'input_planning_group':'planning_group',
'input_position':'ready_position'})
place_center.userdata.box_pose = Pose()
smach.StateMachine.add('GET_POSE_OF_THE_BOX', getPoseOfTheBox(),
transitions={'succeeded':'CLOSE_TO_BOX',
'aborted':'aborted'},
remapping={'output_object_pose':'box_pose'})
place_center.userdata.close_to_box_tolerance = 0.01
smach.StateMachine.add('CLOSE_TO_BOX',
ServiceState(planning_group + '/moveit/set_kinematics_pose',
SetKinematicsPose,
request_cb=eef_pose_request_cb,
response_cb=close_to_box_response_cb,
input_keys=['input_planning_group',
'input_pose',
'input_tolerance']),
transitions={'succeeded':'PLACE_OBJECT',
'aborted':'CLOSE_TO_BOX'},
remapping={'input_planning_group':'planning_group',
'input_pose':'box_pose',
'input_tolerance':'close_to_box_tolerance'})
place_center.userdata.open_gripper = [0.15]
smach.StateMachine.add('PLACE_OBJECT',
ServiceState(namespace + '/gripper',
SetJointPosition,
request_cb=gripper_request_cb,
response_cb=gripper_response_cb,
input_keys=['input_planning_group',
'input_gripper']),
transitions={'succeeded':'SET_HOME_POSITION'},
remapping={'input_planning_group':'planning_group',
'input_gripper':'open_gripper'})
place_center.userdata.init_position = [0.0, -1.5707, 1.37, 0.2258]
smach.StateMachine.add('SET_HOME_POSITION',
ServiceState(planning_group + '/moveit/set_joint_position',
SetJointPosition,
request_cb=joint_position_request_cb,
response_cb=joint_position_response_cb,
input_keys=['input_planning_group',
'input_position']),
transitions={'succeeded':'succeeded'},
remapping={'input_planning_group':'planning_group',
'input_position':'init_position'})
smach.StateMachine.add('PLACE', place_center,
transitions={'succeeded':'succeeded', 'aborted':'aborted'})
sis = smach_ros.IntrospectionServer('server_name', task_center, '/TASKS_CENTER')
sis.start()
# Execute SMACH plan
outcome = task_center.execute()
# Wait for ctrl-c to stop the application
rospy.spin()
sis.stop()
if __name__ == '__main__':
main()