00001
00002
00003 import roslib; roslib.load_manifest('estirabot_apps')
00004 import rospy
00005 import smach
00006 import smach_ros
00007 import tf
00008
00009
00010
00011 from smach import StateMachine, CBState, Iterator
00012 from smach_ros import ServiceState
00013 from actionlib import *
00014 from actionlib.msg import *
00015 from std_msgs.msg import String
00016 from iri_common_smach.utils_msg import build_pose
00017 from object_manipulation_msgs.msg import PickupAction,PickupGoal,PlaceAction,PlaceGoal
00018 from sensor_msgs.msg import PointCloud2, JointState
00019 from iri_deformable_analysis.srv import DoDeformableAnalysis, DoDeformableAnalysisRequest
00020 from estirabot_msgs.msg import PomdpGraspConfig
00021 from estirabot_msgs.srv import obs2action, obs2actionRequest
00022 from geometry_msgs.msg import Transform, PoseStamped, Pose
00023 from pprint import pprint
00024 from std_msgs.msg import Int8, Int32
00025
00026 from iri_common_smach.st_get_pcl import GetPCL
00027 from iri_common_smach.transform_manager import TransformManager
00028 from iri_common_smach.homogeneous_product import *
00029 from iri_common_smach.utils_msg import build_pose_stamped_msg, build_transform_msg
00030 from iri_common_smach.get_keystroke import GetKeyStroke
00031
00032 from iri_wam_smach.sm_wam_move_from_pose import SM_WAM_MoveFromPose
00033
00034 from estirabot_apps_base.utils_pomdp import PomdpConfigFactory
00035 from estirabot_apps_base.sm_move import SM_ESTIRABOT_GoHome
00036 from estirabot_apps_base.sm_deformable_analysis import SM_ESTIRABOT_DeformableAnalysis
00037 from estirabot_apps_base.sm_deformable_analysis import PerformAnalysis
00038 from estirabot_apps_base.sm_generate_grasp import *
00039 from TranslatePomdp2piles import TranslatePomdp
00040
00041 class PlaceHandler():
00042 def __init__(self):
00043 self.next_left_zone = 1
00044 self.next_right_zone = 1
00045
00046 def calculate_place_pose(self, pomdp_config):
00047
00048 if (pomdp_config.place_point == None):
00049 return self.get_basket_pose()
00050
00051 if (pomdp_config.grabbing_zone == pomdp_config.LEFT_ZONE):
00052 return self.get_right_place_pose()
00053 elif (pomdp_config.grabbing_zone == pomdp_config.RIGHT_ZONE):
00054 return self.get_left_place_pose()
00055 else:
00056 rospy.logerr("Value for graspping zone is not LEFT or RIGHT")
00057 return build_home_pose()
00058
00059 def get_basket_pose(self):
00060 return build_pose(-0.165, 0.514, -0.188, 1, 0, 0, 0)
00061
00062 def get_right_place_pose(self):
00063 if (self.next_right_zone == 1):
00064 pose = build_pose(0.422, -0.390, -0.234, 1, 0, 0, 0)
00065 elif (self.next_right_zone == 2):
00066 pose = build_pose(0.584, -0.390, -0.234, 1, 0, 0, 0)
00067 elif (self.next_right_zone == 3):
00068 pose = build_pose(0.633, -0.160, -0.234, 1, 0, 0, 0)
00069 elif (self.next_right_zone == 4):
00070 pose = build_pose(0.476, -0.160, -0.234, 1, 0, 0, 0)
00071 else:
00072 rospy.logerr("Righ pose next zone is out of range: " + str(self.next_right_zone))
00073
00074 self.next_right_zone = self.next_right_zone + 1
00075
00076
00077 if (self.next_right_zone > 4):
00078 self.next_right_zone = 1
00079
00080 return pose
00081
00082 def get_left_place_pose(self):
00083 if (self.next_left_zone == 1):
00084 pose = build_pose(0.422, 0.390, -0.234, 1, 0, 0, 0)
00085 elif (self.next_left_zone == 2):
00086 pose = build_pose(0.584, 0.390, -0.234, 1, 0, 0, 0)
00087 elif (self.next_left_zone == 3):
00088 pose = build_pose(0.633, 0.160, -0.234, 1, 0, 0, 0)
00089 elif (self.next_left_zone == 4):
00090 pose = build_pose(0.476, 0.160, -0.234, 1, 0, 0, 0)
00091 else:
00092 rospy.logerr("Left pose next zone is out of range: " + str(self.next_left_zone))
00093
00094 self.next_left_zone = self.next_left_zone + 1
00095
00096
00097 if (self.next_left_zone > 4):
00098 self.next_left_zone = 1
00099
00100 return pose
00101
00102 class BuildPickupGoalFromTransform(smach.State):
00103 fingers_grasp_configs = []
00104 def __init__(self):
00105 smach.State.__init__(self, outcomes=['success','fail','no_ik_solution'],
00106 input_keys=['grasp_pose','transform'],
00107 output_keys=['sm_grasp_goal'])
00108 self.fingers_grasp_configs.append("GSTO")
00109 self.fingers_grasp_configs.append("SM 700")
00110 self.fingers_grasp_configs.append("GTC")
00111 self.grasp_pose_st_wam = PoseStamped()
00112 self.grasp_pose_st_wam.header.frame_id = '/wam_link0'
00113 self.grasp_pose_st_wam.header.stamp = rospy.Time.now()
00114 self.grasp_pose_st_wam.pose = build_pose(-0.08, -0.54, -0.35, 1, 0, 0, 0)
00115
00116 def execute(self, userdata):
00117
00118 rospy.set_param('/estirabot/skills/grasp/fingers_configuration', self.fingers_grasp_configs)
00119
00120 pprint("Grasp original")
00121 pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00122 pub.publish(self.grasp_pose_st_wam)
00123
00124
00125 pre_grasp_pose_st = PoseStamped()
00126 pre_grasp_pose_st.header = self.grasp_pose_st_wam.header
00127
00128 modified_grasp_pose_st.pose = homogeneous_product_pose_transform(self.grasp_pose_st_wam.pose,
00129 userdata.transform)
00130
00131 pprint("PRE-Grasp modifier applied")
00132 pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00133 pub.publish(pre_grasp_pose_st)
00134
00135
00136 try:
00137 joints_grasp = get_inverse_kinematics_from_pose(modified_grasp_pose_st)
00138
00139
00140 except rospy.ServiceException, e:
00141 return 'no_ik_solution'
00142
00143 userdata.sm_grasp_goal = build_simple_pickup_goal(joints_grasp,
00144 joints_pre_grasp,
00145 self.fingers_grasp_configs)
00146 return 'success'
00147
00148 class TakeFromBasket(smach.State):
00149 fingers_grasp_configs = []
00150 def __init__(self):
00151 smach.State.__init__(self, outcomes=['success','fail','no_ik_solution'],
00152 output_keys=['sm_grasp_goal'])
00153 self.fingers_grasp_configs.append("GSTO")
00154 self.fingers_grasp_configs.append("SM 700")
00155 self.fingers_grasp_configs.append("GTC")
00156 self.grasp_pose_st_wam = PoseStamped()
00157 self.grasp_pose_st_wam.header.frame_id = '/wam_link0'
00158 self.grasp_pose_st_wam.header.stamp = rospy.Time.now()
00159 self.grasp_pose_st_wam.pose = build_pose(-0.08, -0.54, -0.35, 1, 0, 0, 0)
00160
00161 def execute(self, userdata):
00162
00163 rospy.set_param('/estirabot/skills/grasp/fingers_configuration', self.fingers_grasp_configs)
00164
00165 pprint("Grasp original")
00166 pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00167 pub.publish(self.grasp_pose_st_wam)
00168
00169
00170 pre_grasp_pose_st = PoseStamped()
00171 pre_grasp_pose_st.header = self.grasp_pose_st_wam.header
00172
00173 pre_grasp_pose_st.pose = homogeneous_product_pose_transform(self.grasp_pose_st_wam.pose,
00174 build_transform_msg(0, 0, -0.08, 0, 0, 0, 1))
00175 pprint("PRE-Grasp modifier applied")
00176 pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00177 pub.publish(pre_grasp_pose_st)
00178
00179
00180 try:
00181 joints_grasp = get_inverse_kinematics_from_pose(self.grasp_pose_st_wam)
00182 joints_pre_grasp = get_inverse_kinematics_from_pose(pre_grasp_pose_st)
00183
00184
00185 except rospy.ServiceException, e:
00186 return 'no_ik_solution'
00187
00188 userdata.sm_grasp_goal = build_simple_pickup_goal(joints_grasp,
00189 joints_pre_grasp,
00190 self.fingers_grasp_configs)
00191 return 'success'
00192
00193 class FirstAction(smach.State):
00194 def __init__(self):
00195 smach.State.__init__(self, outcomes = ['ok','fail'],
00196 output_keys = ['pomdp_action','place_handler'])
00197
00198 def execute(self, userdata):
00199
00200 request = obs2actionRequest()
00201 request.first = True
00202 handler = rospy.ServiceProxy('/estirabot/skills/planner/obs2action', obs2action)
00203 response = handler(request)
00204
00205 pprint(response)
00206 userdata.pomdp_action = response.action
00207 pub = rospy.Publisher('/log/pomdp/action', Int8, None, False, True)
00208 pub.publish(response.action)
00209
00210 if (not response):
00211 return 'fail'
00212
00213 return 'ok'
00214
00215 class LogPCL(smach.State):
00216 def __init__(self):
00217 smach.State.__init__(self, outcomes=['success','fail'],
00218 input_keys=['sm_pcl_to_log'],
00219 output_keys=[''])
00220
00221 def execute(self, userdata):
00222
00223 pub = rospy.Publisher('/log/pcl_table', PointCloud2, None, False, True)
00224 pub.publish(userdata.sm_pcl_to_log)
00225 return 'success'
00226
00227 class CalculateGrasp(smach.State):
00228 def __init__(self):
00229 smach.State.__init__(self, outcomes=['success','fail','no_ik_solution','all_ik_fail'],
00230 input_keys=['best_grasp_pose','sm_pomdp_config'],
00231 output_keys=['sm_pomdp_config','grasp_goal'])
00232 self.tf_manager = TransformManager()
00233
00234 def execute(self, userdata):
00235
00236 pomdp_config = userdata.sm_pomdp_config
00237 grasp_pose_st = userdata.best_grasp_pose
00238
00239 rospy.set_param('/estirabot/skills/grasp/fingers_configuration', pomdp_config.fingers_grasp_configs)
00240
00241
00242
00243 grasp_pose_st_wam = self.tf_manager.transform_pose('/wam_link0', grasp_pose_st)
00244
00245
00246 grasp_pose_st_wam.pose.orientation.x = 0
00247 grasp_pose_st_wam.pose.orientation.y = 0
00248 grasp_pose_st_wam.pose.orientation.z = 0
00249 grasp_pose_st_wam.pose.orientation.w = 1.0
00250
00251 pprint("Grasp original")
00252 pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00253 pub.publish(grasp_pose_st_wam)
00254
00255
00256 current_modifier = pomdp_config.approach_config.grasp_modifier_used
00257 pprint("Using grasp modifier number: " + str(current_modifier))
00258 real_grasp_st = PoseStamped()
00259 real_grasp_st.header = grasp_pose_st_wam.header
00260 real_grasp_st.pose = homogeneous_product_pose_transform(grasp_pose_st_wam.pose,
00261 pomdp_config.approach_config.grasp_modifiers[current_modifier])
00262 if (real_grasp_st.pose.position.z < -0.282):
00263 real_grasp_st.pose.position.z = -0.282
00264
00265 pprint("Grasp modifier applied")
00266 pub = rospy.Publisher('/debug/grasp/real', PoseStamped, None, False, True)
00267 pub.publish(real_grasp_st)
00268
00269
00270 pre_grasp_pose_st = PoseStamped()
00271 pre_grasp_pose_st.header = grasp_pose_st_wam.header
00272
00273 pre_grasp_pose_st.pose = homogeneous_product_pose_transform(real_grasp_st.pose,
00274 pomdp_config.approach_config.pre_grasp_modifier)
00275 pprint("PRE-Grasp modifier applied")
00276 pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00277 pub.publish(pre_grasp_pose_st)
00278
00279
00280 pub_config = rospy.Publisher('/log/pomdp_config', PomdpGraspConfig, None, False, True)
00281 pub_config.publish(pomdp_config)
00282
00283
00284 try:
00285 joints_grasp = get_inverse_kinematics_from_pose(real_grasp_st)
00286 joints_pre_grasp = get_inverse_kinematics_from_pose(pre_grasp_pose_st)
00287
00288
00289 except rospy.ServiceException, e:
00290
00291 if (current_modifier < len(pomdp_config.approach_config.grasp_modifiers)-1):
00292
00293 pomdp_config.approach_config.grasp_modifier_used = pomdp_config.approach_config.grasp_modifier_used + 1
00294 pomdp_config.approach_config.pre_grasp_modifier
00295 return 'no_ik_solution'
00296 else:
00297
00298 pub = rospy.Publisher('/log/number_of_clothes', Int8, None, False, True)
00299 pub.publish(0)
00300 rospy.logerr("Inverse Kinematics has no solution")
00301 return 'all_ik_fail'
00302
00303
00304
00305
00306 userdata.grasp_goal = build_simple_pickup_goal(joints_grasp,
00307 joints_pre_grasp,
00308 pomdp_config.fingers_grasp_configs)
00309 return 'success'
00310 class CountObjects(smach.State):
00311 def __init__(self):
00312 smach.State.__init__(self, outcomes = ['fail','success'],
00313 input_keys = ['sm_pcl_table_left','sm_pcl_table_right'],
00314 output_keys = ['left_objects','right_objects'])
00315 self.number = -1
00316
00317 sub = rospy.Subscriber("/estirabot/skills/iri_textile_count/num_objects_found",
00318 Int32, self.recieve_number)
00319
00320 def execute(self, userdata):
00321
00322 self.calculate_objects(userdata.sm_pcl_table_left)
00323 userdata.left_objects = self.number
00324 pprint ("Left objects: " + str(self.number))
00325 pub = rospy.Publisher('/debug/observation/left_objects', Int8, None, False, True)
00326 pub.publish(self.number)
00327
00328 rospy.sleep(2)
00329
00330
00331 self.calculate_objects(userdata.sm_pcl_table_right)
00332 userdata.right_objects = self.number
00333 pprint ("Right objects: " + str(self.number))
00334 pub = rospy.Publisher('/debug/observation/right_objects', Int8, None, False, True)
00335 pub.publish(self.number)
00336
00337 return 'success'
00338
00339 def recieve_number(self, data):
00340 self.number = data.data
00341
00342 def calculate_objects(self, pcl):
00343 self.number = -1
00344
00345 pub = rospy.Publisher('/estirabot/skills/table/pcl', PointCloud2, None, False, True)
00346 pub.publish(pcl)
00347
00348 while (self.number == -1 and (not rospy.is_shutdown())):
00349 pprint("waiting")
00350 time.sleep(.1)
00351
00352 class PrePlace(smach.State):
00353 def __init__(self):
00354 smach.State.__init__(self, outcomes = ['fail','success'],
00355 input_keys = ['sm_pomdp_config'],
00356 output_keys = ['pose_st'])
00357
00358 def execute(self, userdata):
00359 tf = Transform()
00360 tf.translation.z = -0.4
00361
00362 pose_stamped = PoseStamped()
00363 pose_stamped.header.frame_id = '/wam_link0'
00364 pose_stamped.header.stamp = rospy.Time.now()
00365 pose_stamped.pose = homogeneous_product_pose_transform(userdata.sm_pomdp_config.place_point, tf)
00366
00367 userdata.pose_st = pose_stamped
00368 return 'success'
00369
00370
00371 class UpdateBelieve(smach.State):
00372 def __init__(self):
00373 smach.State.__init__(self, outcomes = ['fail','finish','continue'],
00374 input_keys = ['left_objects','right_objects'],
00375 output_keys = ['pomdp_action'])
00376
00377 def execute(self, userdata):
00378 request = obs2actionRequest()
00379
00380 right_objs = userdata.right_objects
00381 left_objs = userdata.left_objects
00382
00383 if (right_objs > 3):
00384 right_objs = 4
00385
00386 if (left_objs > 4):
00387 left_objs = 4
00388
00389 request.first = False
00390 request.observation = right_objs * 5 + left_objs
00391 pub = rospy.Publisher('/log/pomdp/observation', Int8, None, False, True)
00392 pub.publish(request.observation)
00393
00394 pprint(request)
00395 handler = rospy.ServiceProxy('/estirabot/skills/planner/obs2action', obs2action)
00396 response = handler(request)
00397
00398 if (not response):
00399 return 'fail'
00400
00401 pprint(response)
00402 if (response.goal_reached == True):
00403 return 'finish'
00404
00405
00406 userdata.pomdp_action = response.action
00407 pub = rospy.Publisher('/log/pomdp/action', Int8, None, False, True)
00408 pub.publish(response.action)
00409
00410 return 'continue'
00411
00412 def get_sm_place_init_goal_callback(userdata, default_goal):
00413 pose_stamped = PoseStamped()
00414 pose_stamped.header.frame_id = '/wam_link0'
00415 pose_stamped.header.stamp = rospy.Time.now()
00416 pose_stamped.pose = build_pose(0.4, -0.4, -0.23, 1, 0, 0, 0)
00417
00418 goal = PlaceGoal()
00419 goal.place_locations.append(pose_stamped)
00420
00421 return goal
00422
00423 def get_sm_grasp_goal_callback(userdata, default_goal):
00424 return userdata.sm_grasp_goal
00425
00426 def get_sm_place_goal_callback(userdata, default_goal):
00427 pose_stamped = PoseStamped()
00428 pose_stamped.header.frame_id = '/wam_link0'
00429 pose_stamped.header.stamp = rospy.Time.now()
00430 pose_stamped.pose = userdata.sm_pomdp_config.place_point
00431
00432 goal = PlaceGoal()
00433 goal.place_locations.append(pose_stamped)
00434
00435 return goal
00436
00437 def construct_main_sm():
00438
00439 factory_home = SM_ESTIRABOT_GoHome()
00440 sm_home = factory_home.build_sm()
00441 factory_move_cartesian = SM_WAM_MoveFromPose('/estirabot/wam_wrapper/joints_move','/estirabot/wam_ik/wamik')
00442 sm_move_cartesian = factory_move_cartesian.build_sm()
00443
00444
00445 sm = StateMachine(outcomes = ['succeeded','aborted'])
00446
00447 with sm:
00448
00449 sm.userdata.place_handler = PlaceHandler()
00450
00451
00452
00453 smach.StateMachine.add('TAKE_FROM_BASKET', TakeFromBasket(),
00454 transitions = { 'success':'DO_GRASP_INIT',
00455 'no_ik_solution':'aborted',
00456 'fail':'aborted'})
00457
00458 smach.StateMachine.add('DO_GRASP_INIT',
00459 smach_ros.SimpleActionState('/estirabot/skills/grasp/pickup',
00460 PickupAction,
00461 goal_cb = get_sm_grasp_goal_callback,
00462 input_keys=['sm_grasp_goal']),
00463 {'succeeded': 'DO_LIFT_INIT',
00464 'preempted': 'aborted',
00465 'aborted' : 'aborted'})
00466
00467 smach.StateMachine.add('DO_LIFT_INIT', sm_home,
00468 transitions={'success' : 'DO_PLACE_INIT',
00469 'aborted' : 'aborted'})
00470
00471 smach.StateMachine.add('DO_PLACE_INIT',
00472 smach_ros.SimpleActionState('/estirabot/skills/iri_place/place',
00473 PlaceAction,
00474 goal_cb = get_sm_place_init_goal_callback),
00475 {'succeeded': 'BACK_TO_HOME_INIT',
00476 'preempted': 'aborted',
00477 'aborted' : 'aborted'})
00478
00479 smach.StateMachine.add('BACK_TO_HOME_INIT', sm_home,
00480 transitions={'success': 'GIVE_FIRST_ACTION',
00481 'aborted' : 'aborted'})
00482
00483 smach.StateMachine.add('GIVE_FIRST_ACTION', FirstAction(),
00484 transitions = { 'ok':'START_ROUND',
00485 'fail':'aborted'},
00486 remapping = { 'pomdp_action' : 'pomdp_action'})
00487
00488 smach.StateMachine.add('START_ROUND', sm_home,
00489 transitions={'success': 'LOG_PCL',
00490 'aborted' : 'aborted'})
00491 smach.StateMachine.add('LOG_PCL',
00492 GetPCL("/estirabot/ceiling_kinect/camera/rgb/points"),
00493 transitions = {'success' : 'LOG_IMAGE',
00494 'fail' : 'aborted'},
00495 remapping = {'pcl_RGB' : 'sm_pcl_to_log'})
00496 smach.StateMachine.add('LOG_IMAGE', LogPCL(),
00497 transitions={'success': 'TRANSLATE_POMDP_ACTION',
00498 'fail' : 'aborted'})
00499
00500
00501 smach.StateMachine.add('TRANSLATE_POMDP_ACTION', TranslatePomdp(),
00502 transitions = { 'image_from_left' : 'GET_KINECT_IMAGE_FROM_LEFT',
00503 'image_from_right' : 'GET_KINECT_IMAGE_FROM_RIGHT',
00504 'fail':'aborted'},
00505 remapping = { 'sm_pomdp_config' : 'sm_pomdp_config'})
00506
00507
00508
00509 smach.StateMachine.add('GET_KINECT_IMAGE_FROM_LEFT',
00510 GetPCL("/estirabot/skills/table/left/pcl"),
00511 transitions = {'success' : 'PERFORM_ANALISYS',
00512 'fail' : 'aborted'},
00513 remapping = {'pcl_RGB' : 'sm_pcl_output'})
00514
00515
00516 smach.StateMachine.add('GET_KINECT_IMAGE_FROM_RIGHT',
00517 GetPCL("/estirabot/skills/table/right/pcl"),
00518 transitions = {'success' : 'PERFORM_ANALISYS',
00519 'fail' : 'aborted'},
00520 remapping = {'pcl_RGB' : 'sm_pcl_output'})
00521
00522
00523 smach.StateMachine.add('PERFORM_ANALISYS', PerformAnalysis(),
00524 transitions = {'success' : 'CALCULATE_GRASP',
00525 'timeout' : 'PERFORM_ANALISYS',
00526 'fail' : 'aborted'},
00527 remapping = {'pcl_RGB' : 'sm_pcl_output',
00528 'best_grasp_pose' : 'sm_best_grasp_pose',
00529 'deformable_config' : 'sm_pomdp_config'})
00530
00531 smach.StateMachine.add('CALCULATE_GRASP', CalculateGrasp(),
00532 transitions = {'success' : 'DO_GRASP',
00533 'no_ik_solution' : 'CALCULATE_GRASP',
00534 'fail' : 'aborted',
00535 'all_ik_fail' : 'GET_TABLE_IMAGE_FROM_LEFT'},
00536 remapping = {'pcl_RGB' : 'sm_pcl_output',
00537 'best_grasp_pose' : 'sm_best_grasp_pose',
00538 'grasp_goal' : 'sm_grasp_goal'})
00539
00540 smach.StateMachine.add('DO_GRASP',
00541 smach_ros.SimpleActionState('/estirabot/skills/grasp/pickup',
00542 PickupAction,
00543 goal_cb = get_sm_grasp_goal_callback,
00544 input_keys=['sm_grasp_goal']),
00545 {'succeeded': 'DO_LIFT',
00546 'preempted': 'aborted',
00547 'aborted' : 'aborted'})
00548
00549 smach.StateMachine.add('DO_LIFT', sm_home,
00550 transitions={'success' : 'DO_PRE_PLACE',
00551 'aborted' : 'aborted'})
00552
00553 smach.StateMachine.add('DO_PRE_PLACE', PrePlace(),
00554 transitions={'success' : 'DO_MOVE',
00555 'fail' : 'aborted'},
00556 remapping = {'pose_st' : 'sm_pose_st'})
00557
00558 smach.StateMachine.add('DO_MOVE', sm_move_cartesian,
00559 transitions={'success' : 'DO_PLACE',
00560 'aborted' : 'aborted',
00561 'no_kinematic_solution' : 'DO_PLACE'},
00562 remapping = {'pose_st' : 'sm_pose_st'})
00563
00564
00565 smach.StateMachine.add('DO_PLACE',
00566 smach_ros.SimpleActionState('/estirabot/skills/iri_place/place',
00567 PlaceAction,
00568 goal_cb = get_sm_place_goal_callback,
00569 input_keys=['sm_pomdp_config']),
00570 {'succeeded': 'BACK_TO_HOME',
00571 'preempted': 'aborted',
00572 'aborted' : 'aborted'})
00573
00574 smach.StateMachine.add('BACK_TO_HOME', sm_home,
00575 transitions={'success': 'GET_TABLE_IMAGE_FROM_LEFT',
00576 'aborted' : 'aborted'})
00577
00578
00579
00580
00581 smach.StateMachine.add('GET_TABLE_IMAGE_FROM_LEFT',
00582 GetPCL("/estirabot/skills/table/left/pcl"),
00583 transitions = {'success' : 'GET_TABLE_IMAGE_FROM_RIGHT',
00584 'fail' : 'aborted'},
00585 remapping = {'pcl_RGB' : 'sm_pcl_table_left'})
00586
00587 smach.StateMachine.add('GET_TABLE_IMAGE_FROM_RIGHT',
00588 GetPCL("/estirabot/skills/table/right/pcl"),
00589 transitions = {'success' : 'COUNT_OBJECTS',
00590 'fail' : 'aborted'},
00591 remapping = {'pcl_RGB' : 'sm_pcl_table_right'})
00592
00593 smach.StateMachine.add('COUNT_OBJECTS', CountObjects(),
00594 transitions={'success' : 'UPDATE_BELIEVE_STATE',
00595 'fail' : 'aborted'})
00596
00597 smach.StateMachine.add('UPDATE_BELIEVE_STATE', UpdateBelieve(),
00598 transitions={'continue' : 'START_ROUND',
00599 'finish' : 'succeeded',
00600 'fail' : 'aborted'})
00601
00602 return sm
00603
00604 def main():
00605 rospy.init_node("pomdp_sm")
00606 sm_main = construct_main_sm()
00607
00608
00609 sis = smach_ros.IntrospectionServer('estirabot_smach_replicable', sm_main,
00610 '/estirabot_smach_replicable')
00611
00612 sis.start()
00613
00614 outcome = sm_main.execute()
00615
00616 rospy.spin()
00617 sis.stop()
00618
00619 if __name__ == "__main__":
00620 main()