pomdp_execution_basket.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import roslib; roslib.load_manifest('estirabot_apps')
00004 import rospy
00005 import smach
00006 import smach_ros
00007 import tf
00008 
00009 #from pomdp_create_model import *
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 
00040 class PlaceHandler():
00041     def __init__(self):
00042         self.next_left_zone  = 1
00043         self.next_right_zone = 1
00044 
00045     def calculate_place_pose(self, pomdp_config):
00046         # If place_point is None it implies special basket
00047         if (pomdp_config.place_point == None):
00048             return self.get_basket_pose()
00049 
00050         if (pomdp_config.grabbing_zone == pomdp_config.LEFT_ZONE):
00051             return self.get_right_place_pose()
00052         elif (pomdp_config.grabbing_zone == pomdp_config.RIGHT_ZONE):
00053             return self.get_left_place_pose()
00054         else:
00055             rospy.logerr("Value for graspping zone is not LEFT or RIGHT")
00056             return build_home_pose()
00057 
00058     def get_basket_pose(self):
00059         return build_pose(-0.165, 0.514, -0.188, 1, 0, 0, 0)
00060 
00061     def get_right_place_pose(self):
00062         if (self.next_right_zone == 1):
00063             pose = build_pose(0.422, -0.390, -0.234, 1, 0, 0, 0)
00064         elif (self.next_right_zone == 2):
00065             pose = build_pose(0.584, -0.390, -0.234, 1, 0, 0, 0)
00066         elif (self.next_right_zone == 3):
00067             pose = build_pose(0.633, -0.160, -0.234, 1, 0, 0, 0)
00068         elif (self.next_right_zone == 4):
00069             pose = build_pose(0.476, -0.160, -0.234, 1, 0, 0, 0)
00070         else:
00071             rospy.logerr("Righ pose next zone is out of range: " + str(self.next_right_zone))
00072 
00073         self.next_right_zone = self.next_right_zone + 1
00074 
00075         # reset to 1 again
00076         if (self.next_right_zone > 4):
00077             self.next_right_zone = 1
00078 
00079         return pose
00080 
00081     def get_left_place_pose(self):
00082         if (self.next_left_zone == 1):
00083             pose = build_pose(0.422, 0.390, -0.234, 1, 0, 0, 0)
00084         elif (self.next_left_zone == 2):
00085             pose = build_pose(0.584, 0.390, -0.234, 1, 0, 0, 0)
00086         elif (self.next_left_zone == 3):
00087             pose = build_pose(0.633, 0.160, -0.234, 1, 0, 0, 0)
00088         elif (self.next_left_zone == 4):
00089             pose = build_pose(0.476, 0.160, -0.234, 1, 0, 0, 0)
00090         else:
00091             rospy.logerr("Left pose next zone is out of range: " + str(self.next_left_zone))
00092 
00093         self.next_left_zone = self.next_left_zone + 1
00094 
00095         # reset to 1 again
00096         if (self.next_left_zone > 4):
00097             self.next_left_zone = 1
00098 
00099         return pose
00100 
00101 def get_config_from_pomdp_action(pomdp_action):
00102 
00103     if (pomdp_action > 21):
00104         rospy.logfatal("Pomdp action id out of range: " + str(pomdp_action))
00105 
00106     server = PomdpConfigFactory()
00107 
00108     if  (pomdp_action == 20):
00109         magic_number = 114
00110     elif (pomdp_action == 21):
00111         magic_number = 114
00112     elif (pomdp_action % 10 == 0):
00113         magic_number = 1
00114     elif (pomdp_action % 10 == 1):
00115         magic_number = 3
00116     elif (pomdp_action % 10 == 2):
00117         magic_number = 5
00118     elif (pomdp_action % 10 == 3):
00119         magic_number = 11
00120     elif (pomdp_action % 10 == 4):
00121         magic_number = 14
00122     elif (pomdp_action % 10 == 5):
00123         magic_number = 101
00124     elif (pomdp_action % 10 == 6):
00125         magic_number = 103
00126     elif (pomdp_action % 10 == 7):
00127         magic_number = 105
00128     elif (pomdp_action % 10 == 8):
00129         magic_number = 111
00130     elif (pomdp_action % 10 == 9):
00131         magic_number = 114
00132 
00133     # From magic number get configuration
00134     config = server.get_instance(magic_number)
00135 
00136     # Also set the grabbing zone
00137     if (pomdp_action == 20):
00138         config.grabbing_zone = config.RIGHT_ZONE
00139     elif (pomdp_action == 21):
00140         config.grabbing_zone = config.LEFT_ZONE
00141     elif (pomdp_action > 9):
00142         config.grabbing_zone = config.LEFT_ZONE
00143     else:
00144         config.grabbing_zone = config.RIGHT_ZONE
00145 
00146     # 20 and 21 should get an special value for place.
00147     # Hack for this is set place_point to None and check for it
00148     # in PlaceHandler. Dirty as hell.
00149     if (pomdp_action == 20) or (pomdp_action == 21):
00150         config.place_point = None
00151 
00152     return config
00153 
00154 class BuildPickupGoalFromTranform(smach.State):
00155     fingers_grasp_configs = []
00156     def __init__(self):
00157         smach.State.__init__(self, outcomes=['success','fail','no_ik_solution'],
00158                                    input_keys=['grasp_pose','transform'],
00159                                    output_keys=['sm_grasp_goal'])
00160         self.fingers_grasp_configs.append("SM 700")
00161         self.fingers_grasp_configs.append("GTC")
00162         self.grasp_pose_st_wam                 = PoseStamped()
00163         self.grasp_pose_st_wam.header.frame_id = '/wam_link0'
00164         self.grasp_pose_st_wam.header.stamp    = rospy.Time.now()
00165         self.grasp_pose_st_wam.pose = build_pose(-0.08, -0.54, -0.35, 1, 0, 0, 0)
00166 
00167     def execute(self, userdata):
00168         # shortcuts
00169         rospy.set_param('/estirabot/skills/grasp/fingers_configuration', self.fingers_grasp_configs)
00170 
00171         pprint("Grasp original")
00172         pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00173         pub.publish(self.grasp_pose_st_wam)
00174 
00175         # pre-grasp posture is relative to real_grasp pose
00176         pre_grasp_pose_st        = PoseStamped()
00177         pre_grasp_pose_st.header = self.grasp_pose_st_wam.header
00178 
00179         modified_grasp_pose_st.pose = homogeneous_product_pose_transform(self.grasp_pose_st_wam.pose,
00180                                                                          userdata.transform)
00181 
00182         pprint("PRE-Grasp modifier applied")
00183         pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00184         pub.publish(pre_grasp_pose_st)
00185 
00186         # For both grasp and pre-grasp we need the inverse kinematics and get joinst positions
00187         try:
00188             joints_grasp     = get_inverse_kinematics_from_pose(modified_grasp_pose_st)
00189 
00190         #except NoKinematicSolutionException, e:
00191         except rospy.ServiceException, e:
00192             return 'no_ik_solution'
00193 
00194         userdata.sm_grasp_goal =  build_simple_pickup_goal(joints_grasp,
00195                                                         joints_pre_grasp,
00196                                                         self.fingers_grasp_configs)
00197         return 'success'
00198 
00199 class TakeFromBasket(smach.State):
00200     fingers_grasp_configs = []
00201     def __init__(self):
00202         smach.State.__init__(self, outcomes=['success','fail','no_ik_solution'],
00203                                    output_keys=['sm_grasp_goal'])
00204         self.fingers_grasp_configs.append("GSTO")
00205         self.fingers_grasp_configs.append("SM 700")
00206         self.fingers_grasp_configs.append("GTC")
00207         self.grasp_pose_st_wam                 = PoseStamped()
00208         self.grasp_pose_st_wam.header.frame_id = '/wam_link0'
00209         self.grasp_pose_st_wam.header.stamp    = rospy.Time.now()
00210         self.grasp_pose_st_wam.pose = build_pose(-0.08, -0.54, -0.35, 1, 0, 0, 0)
00211 
00212     def execute(self, userdata):
00213         # shortcuts
00214         rospy.set_param('/estirabot/skills/grasp/fingers_configuration', self.fingers_grasp_configs)
00215 
00216         pprint("Grasp original")
00217         pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00218         pub.publish(self.grasp_pose_st_wam)
00219 
00220         # pre-grasp posture is relative to real_grasp pose
00221         pre_grasp_pose_st        = PoseStamped()
00222         pre_grasp_pose_st.header = self.grasp_pose_st_wam.header
00223 
00224         pre_grasp_pose_st.pose = homogeneous_product_pose_transform(self.grasp_pose_st_wam.pose,
00225                                                           build_transform_msg(0, 0, -0.08, 0, 0, 0, 1))
00226         pprint("PRE-Grasp modifier applied")
00227         pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00228         pub.publish(pre_grasp_pose_st)
00229 
00230         # For both grasp and pre-grasp we need the inverse kinematics and get joinst positions
00231         try:
00232             joints_grasp     = get_inverse_kinematics_from_pose(self.grasp_pose_st_wam)
00233             joints_pre_grasp = get_inverse_kinematics_from_pose(pre_grasp_pose_st)
00234 
00235         #except NoKinematicSolutionException, e:
00236         except rospy.ServiceException, e:
00237             return 'no_ik_solution'
00238 
00239         userdata.sm_grasp_goal =  build_simple_pickup_goal(joints_grasp,
00240                                                         joints_pre_grasp,
00241                                                         self.fingers_grasp_configs)
00242         return 'success'
00243 
00244 class FirstAction(smach.State):
00245     def __init__(self):
00246         smach.State.__init__(self, outcomes    = ['ok','fail'],
00247                                    output_keys = ['pomdp_action','place_handler'])
00248 
00249     def execute(self, userdata):
00250         # Config and launch the deformable analysis
00251         request = obs2actionRequest()
00252         request.first       = True
00253         handler = rospy.ServiceProxy('/estirabot/skills/planner/obs2action', obs2action)
00254         response = handler(request)
00255 
00256         pprint(response)
00257         userdata.pomdp_action = response.action
00258         pub = rospy.Publisher('/log/pomdp/action', Int8, None, False, True)
00259         pub.publish(response.action)
00260 
00261         if (not response):
00262             return 'fail'
00263 
00264         return 'ok'
00265 
00266 class LogPCL(smach.State):
00267     def __init__(self):
00268         smach.State.__init__(self, outcomes=['success','fail'],
00269                                    input_keys=['sm_pcl_to_log'],
00270                                    output_keys=[''])
00271 
00272     def execute(self, userdata):
00273         # Log the PCL
00274         pub = rospy.Publisher('/log/pcl_table', PointCloud2,  None, False, True)
00275         pub.publish(userdata.sm_pcl_to_log)
00276         return 'success'
00277 
00278 
00279 class TranslatePomdp(smach.State):
00280     def __init__(self):
00281         smach.State.__init__(self, outcomes    = ['fail','image_from_left','image_from_right'],
00282                                    input_keys  = ['pomdp_action','place_handler'],
00283                                    output_keys = ['sm_pomdp_config','place_handler'])
00284 
00285     def execute(self, userdata):
00286         # Stupid trick to not declare sm_pomdp_config as input (SMACH goodies)
00287         config                    = get_config_from_pomdp_action(userdata.pomdp_action)
00288         config.place_point        = userdata.place_handler.calculate_place_pose(config)
00289 
00290         userdata.sm_pomdp_config = config
00291 
00292         pub_config = rospy.Publisher('/debug/pomdp_config', PomdpGraspConfig, None, False, True)
00293         pub_config.publish(config)
00294         pprint(config)
00295 
00296         if (config.grabbing_zone == config.LEFT_ZONE):
00297             return 'image_from_left'
00298         else:
00299             return 'image_from_right'
00300 
00301 class CalculateGrasp(smach.State):
00302     def __init__(self):
00303         smach.State.__init__(self, outcomes=['success','fail','no_ik_solution','all_ik_fail'],
00304                                    input_keys=['best_grasp_pose','sm_pomdp_config'],
00305                                    output_keys=['sm_pomdp_config','grasp_goal'])
00306         self.tf_manager = TransformManager()
00307 
00308     def execute(self, userdata):
00309         # shorcuts
00310         pomdp_config  = userdata.sm_pomdp_config
00311         grasp_pose_st = userdata.best_grasp_pose
00312 
00313         rospy.set_param('/estirabot/skills/grasp/fingers_configuration', pomdp_config.fingers_grasp_configs)
00314 
00315         # grasp_pose_st comes referecence to camera frame_id
00316         # we need to transform the message to wam base frame /wam_link0 
00317         grasp_pose_st_wam = self.tf_manager.transform_pose('/wam_link0', grasp_pose_st)
00318 
00319         # Orientation is fixed so ignoring previous
00320         grasp_pose_st_wam.pose.orientation.x = 0
00321         grasp_pose_st_wam.pose.orientation.y = 0
00322         grasp_pose_st_wam.pose.orientation.z = 0
00323         grasp_pose_st_wam.pose.orientation.w = 1.0
00324 
00325         pprint("Grasp original")
00326         pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00327         pub.publish(grasp_pose_st_wam)
00328 
00329         # real grasp is build applying grasp modifier to grasp_pose
00330         current_modifier     = pomdp_config.approach_config.grasp_modifier_used
00331         pprint("Using grasp modifier number: " + str(current_modifier))
00332         real_grasp_st        = PoseStamped()
00333         real_grasp_st.header = grasp_pose_st_wam.header
00334         real_grasp_st.pose   = homogeneous_product_pose_transform(grasp_pose_st_wam.pose,
00335                                                           pomdp_config.approach_config.grasp_modifiers[current_modifier])
00336         if (real_grasp_st.pose.position.z < -0.282):
00337             real_grasp_st.pose.position.z = -0.282
00338 
00339         pprint("Grasp modifier applied")
00340         pub = rospy.Publisher('/debug/grasp/real', PoseStamped, None, False, True)
00341         pub.publish(real_grasp_st)
00342 
00343         # pre-grasp posture is relative to real_grasp pose
00344         pre_grasp_pose_st        = PoseStamped()
00345         pre_grasp_pose_st.header = grasp_pose_st_wam.header
00346 
00347         pre_grasp_pose_st.pose = homogeneous_product_pose_transform(real_grasp_st.pose,
00348                                                           pomdp_config.approach_config.pre_grasp_modifier)
00349         pprint("PRE-Grasp modifier applied")
00350         pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00351         pub.publish(pre_grasp_pose_st)
00352 
00353         # GRASP is Kinematic compliant so save and log the final configuration
00354         pub_config = rospy.Publisher('/log/pomdp_config', PomdpGraspConfig, None, False, True)
00355         pub_config.publish(pomdp_config)
00356 
00357         # For both grasp and pre-grasp we need the inverse kinematics and get joinst positions
00358         try:
00359             joints_grasp     = get_inverse_kinematics_from_pose(real_grasp_st)
00360             joints_pre_grasp = get_inverse_kinematics_from_pose(pre_grasp_pose_st)
00361 
00362         #except NoKinematicSolutionException, e:
00363         except rospy.ServiceException, e:
00364             # Let's go to next grasp_modifier (if any)
00365             if (current_modifier < len(pomdp_config.approach_config.grasp_modifiers)-1):
00366                 # Mark next configuration to use 
00367                 pomdp_config.approach_config.grasp_modifier_used = pomdp_config.approach_config.grasp_modifier_used + 1
00368                 pomdp_config.approach_config.pre_grasp_modifier
00369                 return 'no_ik_solution'
00370             else:
00371                 # all modifiers were tested and are not valid. Return error
00372                 pub = rospy.Publisher('/log/number_of_clothes', Int8, None, False, True)
00373                 pub.publish(0)
00374                 rospy.logerr("Inverse Kinematics has no solution")
00375                 return 'all_ik_fail'
00376 
00377         #     rospy.logerr("WamIK service failed")
00378         #           return 'fail'
00379 
00380         userdata.grasp_goal =  build_simple_pickup_goal(joints_grasp,
00381                                                         joints_pre_grasp,
00382                                                         pomdp_config.fingers_grasp_configs)
00383         return 'success'
00384 class CountObjects(smach.State):
00385     def __init__(self):
00386         smach.State.__init__(self, outcomes    = ['fail','success'],
00387                                    input_keys  = ['sm_pcl_table_left','sm_pcl_table_right'],
00388                                    output_keys = ['left_objects','right_objects'])
00389         self.number = -1
00390         # Subscribe to count numbers
00391         sub = rospy.Subscriber("/estirabot/skills/iri_textile_count/num_objects_found",
00392                                Int32, self.recieve_number)
00393 
00394     def execute(self, userdata):
00395         # Left objects
00396         self.calculate_objects(userdata.sm_pcl_table_left)
00397         userdata.left_objects = self.number
00398         pprint ("Left objects: " + str(self.number))
00399         pub = rospy.Publisher('/debug/observation/left_objects', Int8, None, False, True)
00400         pub.publish(self.number)
00401 
00402         rospy.sleep(2)
00403 
00404         # Right objects
00405         self.calculate_objects(userdata.sm_pcl_table_right)
00406         userdata.right_objects = self.number
00407         pprint ("Right objects: " + str(self.number))
00408         pub = rospy.Publisher('/debug/observation/right_objects', Int8, None, False, True)
00409         pub.publish(self.number)
00410 
00411         return 'success'
00412 
00413     def recieve_number(self, data):
00414         self.number = data.data
00415 
00416     def calculate_objects(self, pcl):
00417         self.number = -1
00418         # Publish the pcl in /estirabot/skills/table/pcl
00419         pub = rospy.Publisher('/estirabot/skills/table/pcl', PointCloud2, None, False, True)
00420         pub.publish(pcl)
00421         # Wait to recieve the callback
00422         while (self.number == -1 and (not rospy.is_shutdown())):
00423             pprint("waiting")
00424             time.sleep(.1)
00425 
00426 class PrePlace(smach.State):
00427     def __init__(self):
00428         smach.State.__init__(self, outcomes     = ['fail','success'],
00429                                    input_keys   = ['sm_pomdp_config'],
00430                                    output_keys   = ['pose_st'])
00431 
00432     def execute(self, userdata):
00433         tf = Transform()
00434         tf.translation.z = -0.4
00435 
00436         pose_stamped                 = PoseStamped()
00437         pose_stamped.header.frame_id = '/wam_link0'
00438         pose_stamped.header.stamp    = rospy.Time.now()
00439         pose_stamped.pose = homogeneous_product_pose_transform(userdata.sm_pomdp_config.place_point, tf)
00440 
00441         userdata.pose_st = pose_stamped
00442         return 'success'
00443 
00444 
00445 class UpdateBelieve(smach.State):
00446     def __init__(self):
00447         smach.State.__init__(self, outcomes     = ['fail','finish','continue'],
00448                                    input_keys   = ['left_objects','right_objects'],
00449                                    output_keys  = ['pomdp_action'])
00450 
00451     def execute(self, userdata):
00452         request = obs2actionRequest()
00453         # Build observation
00454         right_objs = userdata.right_objects
00455         left_objs  = userdata.left_objects
00456 
00457         if (right_objs > 3):
00458             right_objs = 4
00459 
00460         if (left_objs > 4):
00461             left_objs = 4
00462         
00463         request.first       = False
00464         request.observation = right_objs * 5 + left_objs
00465         pub = rospy.Publisher('/log/pomdp/observation', Int8, None, False, True)
00466         pub.publish(request.observation)
00467 
00468         pprint(request)
00469         handler = rospy.ServiceProxy('/estirabot/skills/planner/obs2action', obs2action)
00470         response = handler(request)
00471 
00472         if (not response):
00473             return 'fail'
00474 
00475         pprint(response)
00476         if (response.goal_reached == True):
00477             return 'finish'
00478 
00479     
00480         userdata.pomdp_action = response.action
00481         pub = rospy.Publisher('/log/pomdp/action', Int8, None, False, True)
00482         pub.publish(response.action)
00483 
00484         return 'continue'
00485 
00486 def get_sm_place_init_goal_callback(userdata, default_goal):
00487     pose_stamped                 = PoseStamped()
00488     pose_stamped.header.frame_id = '/wam_link0'
00489     pose_stamped.header.stamp    = rospy.Time.now()
00490     pose_stamped.pose            = build_pose(0.4, -0.4, -0.23, 1, 0, 0, 0)
00491 
00492     goal = PlaceGoal()
00493     goal.place_locations.append(pose_stamped)
00494 
00495     return goal
00496 
00497 def get_sm_grasp_goal_callback(userdata, default_goal):
00498     return userdata.sm_grasp_goal
00499 
00500 def get_sm_place_goal_callback(userdata, default_goal):
00501     pose_stamped                 = PoseStamped()
00502     pose_stamped.header.frame_id = '/wam_link0'
00503     pose_stamped.header.stamp    = rospy.Time.now()
00504     pose_stamped.pose            = userdata.sm_pomdp_config.place_point
00505 
00506     goal = PlaceGoal()
00507     goal.place_locations.append(pose_stamped)
00508 
00509     return goal
00510 
00511 def construct_main_sm():
00512 
00513     factory_home = SM_ESTIRABOT_GoHome()
00514     sm_home = factory_home.build_sm()
00515     factory_move_cartesian = SM_WAM_MoveFromPose('/estirabot/wam_wrapper/joints_move','/estirabot/wam_ik/wamik')
00516     sm_move_cartesian = factory_move_cartesian.build_sm()
00517 
00518 
00519     sm = StateMachine(outcomes = ['succeeded','aborted'])
00520 
00521     with sm:
00522         # Create the place handler
00523         sm.userdata.place_handler = PlaceHandler()
00524 
00525         #TODO machine-in-machine instead of duplicates 
00526         #it's better to build up a standalone statie similar to DO_GRASP
00527         smach.StateMachine.add('TAKE_FROM_BASKET', TakeFromBasket(),
00528                 transitions = { 'success':'DO_GRASP_INIT',
00529                                 'no_ik_solution':'aborted',
00530                                 'fail':'aborted'})
00531         # 0.1 GRASP
00532         smach.StateMachine.add('DO_GRASP_INIT',
00533                                smach_ros.SimpleActionState('/estirabot/skills/grasp/pickup',
00534                                                           PickupAction,
00535                                                           goal_cb = get_sm_grasp_goal_callback,
00536                                                           input_keys=['sm_grasp_goal']),
00537                                {'succeeded': 'DO_LIFT_INIT',
00538                                 'preempted': 'aborted',
00539                                 'aborted'  : 'aborted'})
00540         # 0.2 LIFT
00541         smach.StateMachine.add('DO_LIFT_INIT', sm_home,
00542                         transitions={'success' : 'DO_PLACE_INIT',
00543                                      'aborted'    : 'aborted'})
00544         # 0.4 DO PLACE
00545         smach.StateMachine.add('DO_PLACE_INIT',
00546                        smach_ros.SimpleActionState('/estirabot/skills/iri_place/place',
00547                                                   PlaceAction,
00548                                                   goal_cb = get_sm_place_init_goal_callback),
00549                        {'succeeded': 'BACK_TO_HOME_INIT',
00550                         'preempted': 'aborted',
00551                         'aborted'  : 'aborted'})
00552 
00553         smach.StateMachine.add('BACK_TO_HOME_INIT', sm_home,
00554                           transitions={'success': 'GIVE_FIRST_ACTION',
00555                                        'aborted'   : 'aborted'})
00556 
00557         smach.StateMachine.add('GIVE_FIRST_ACTION', FirstAction(),
00558                 transitions = { 'ok':'START_ROUND',
00559                                 'fail':'aborted'},
00560                 remapping   = { 'pomdp_action' : 'pomdp_action'})
00561 
00562         smach.StateMachine.add('START_ROUND', sm_home,
00563                           transitions={'success': 'LOG_PCL',
00564                                        'aborted'   : 'aborted'})
00565         smach.StateMachine.add('LOG_PCL', 
00566                                 GetPCL("/estirabot/ceiling_kinect/camera/rgb/points"),
00567                 transitions = {'success' : 'LOG_IMAGE',
00568                                'fail'    : 'aborted'},
00569                 remapping   = {'pcl_RGB'  : 'sm_pcl_to_log'})
00570         smach.StateMachine.add('LOG_IMAGE', LogPCL(),
00571                           transitions={'success': 'TRANSLATE_POMDP_ACTION',
00572                                        'fail'   : 'aborted'})
00573 
00574         # 2. CALCULATE GRASP POINT
00575         smach.StateMachine.add('TRANSLATE_POMDP_ACTION', TranslatePomdp(),
00576             transitions = { 'image_from_left'  : 'GET_KINECT_IMAGE_FROM_LEFT',
00577                             'image_from_right' : 'GET_KINECT_IMAGE_FROM_RIGHT',
00578                             'fail':'aborted'},
00579             remapping   = { 'sm_pomdp_config' : 'sm_pomdp_config'})
00580 
00581 
00582         # 2.1.a GET KINECT IMAGE FROM LEFT
00583         smach.StateMachine.add('GET_KINECT_IMAGE_FROM_LEFT', 
00584                                 GetPCL("/estirabot/skills/table/left/pcl"),
00585                 transitions = {'success' : 'PERFORM_ANALISYS',
00586                                'fail'    : 'aborted'},
00587                 remapping   = {'pcl_RGB'  : 'sm_pcl_output'})
00588 
00589         # 2.1.b GET KINECT IMAGE FROM RIGHT
00590         smach.StateMachine.add('GET_KINECT_IMAGE_FROM_RIGHT', 
00591                               GetPCL("/estirabot/skills/table/right/pcl"),
00592                 transitions = {'success' : 'PERFORM_ANALISYS',
00593                                'fail'    : 'aborted'},
00594                 remapping   = {'pcl_RGB'  : 'sm_pcl_output'})
00595 
00596         # 2.2 ANALYSIS
00597         smach.StateMachine.add('PERFORM_ANALISYS', PerformAnalysis(),
00598                 transitions = {'success'        : 'CALCULATE_GRASP',
00599                                'timeout'        : 'PERFORM_ANALISYS', # hack relaunch since descriptors died
00600                                'fail'           : 'aborted'},
00601                 remapping   = {'pcl_RGB'         : 'sm_pcl_output',
00602                                'best_grasp_pose' : 'sm_best_grasp_pose',
00603                                'deformable_config' : 'sm_pomdp_config'}) # compatibles
00604         # 2.3 CALCULATE GRASP
00605         smach.StateMachine.add('CALCULATE_GRASP', CalculateGrasp(),
00606                 transitions = {'success'        : 'DO_GRASP',
00607                                'no_ik_solution' : 'CALCULATE_GRASP',
00608                                'fail'           : 'aborted',
00609                                'all_ik_fail'    : 'GET_TABLE_IMAGE_FROM_LEFT'},
00610                 remapping   = {'pcl_RGB'         : 'sm_pcl_output',
00611                                'best_grasp_pose' : 'sm_best_grasp_pose',
00612                                'grasp_goal'      : 'sm_grasp_goal'})
00613         # 3.1 GRASP
00614         smach.StateMachine.add('DO_GRASP',
00615                                smach_ros.SimpleActionState('/estirabot/skills/grasp/pickup',
00616                                                           PickupAction,
00617                                                           goal_cb = get_sm_grasp_goal_callback,
00618                                                           input_keys=['sm_grasp_goal']),
00619                                {'succeeded': 'DO_LIFT',
00620                                 'preempted': 'aborted',
00621                                 'aborted'  : 'aborted'})
00622         # 3.2 LIFT
00623         smach.StateMachine.add('DO_LIFT', sm_home,
00624                         transitions={'success' : 'DO_PRE_PLACE',
00625                                      'aborted'    : 'aborted'})
00626         # 3.3.1 DO PRE PLACE
00627         smach.StateMachine.add('DO_PRE_PLACE', PrePlace(),
00628                         transitions={'success' : 'DO_MOVE',
00629                                      'fail'    : 'aborted'},
00630                         remapping = {'pose_st' : 'sm_pose_st'})
00631 
00632         smach.StateMachine.add('DO_MOVE', sm_move_cartesian,
00633                         transitions={'success' : 'DO_PLACE',
00634                                      'aborted'    : 'aborted',
00635                                      'no_kinematic_solution'    : 'DO_PLACE'}, #TODO recompute pre place point 
00636                         remapping = {'pose_st' : 'sm_pose_st'})
00637         #
00638         # 3.3.2 DO PLACE
00639         smach.StateMachine.add('DO_PLACE',
00640                        smach_ros.SimpleActionState('/estirabot/skills/iri_place/place',
00641                                                   PlaceAction,
00642                                                   goal_cb = get_sm_place_goal_callback,
00643                                                   input_keys=['sm_pomdp_config']),
00644                        {'succeeded': 'BACK_TO_HOME',
00645                         'preempted': 'aborted',
00646                         'aborted'  : 'aborted'})
00647 
00648         smach.StateMachine.add('BACK_TO_HOME', sm_home,
00649                           transitions={'success': 'GET_TABLE_IMAGE_FROM_LEFT',
00650                                        'aborted'   : 'aborted'})
00651 
00652 
00653         # 4. OBSERVATION
00654         # 4.1 GET PCL FROM LEFT
00655         smach.StateMachine.add('GET_TABLE_IMAGE_FROM_LEFT', 
00656                       GetPCL("/estirabot/skills/table/left/pcl"),
00657                 transitions = {'success' : 'GET_TABLE_IMAGE_FROM_RIGHT',
00658                                'fail'    : 'aborted'},
00659                 remapping   = {'pcl_RGB'  : 'sm_pcl_table_left'})
00660         # 4.2 GET PCL FROM RIGHT
00661         smach.StateMachine.add('GET_TABLE_IMAGE_FROM_RIGHT', 
00662                       GetPCL("/estirabot/skills/table/right/pcl"),
00663                 transitions = {'success' : 'COUNT_OBJECTS',
00664                                'fail'    : 'aborted'},
00665                 remapping   = {'pcl_RGB'  : 'sm_pcl_table_right'})
00666         # 4.3 GET NUMBER OF OBJECTS
00667         smach.StateMachine.add('COUNT_OBJECTS', CountObjects(),
00668                         transitions={'success' : 'UPDATE_BELIEVE_STATE',
00669                                      'fail'    : 'aborted'})
00670         # 5 UPDATE BELIEVE STATE
00671         smach.StateMachine.add('UPDATE_BELIEVE_STATE', UpdateBelieve(),
00672                         transitions={'continue' : 'START_ROUND',
00673                                      'finish'   : 'succeeded',
00674                                      'fail'     : 'aborted'})
00675 
00676     return sm
00677 
00678 def main():
00679     rospy.init_node("pomdp_sm")
00680     sm_main = construct_main_sm()
00681 
00682     # Run state machine introspection server for smach viewer
00683     sis = smach_ros.IntrospectionServer('estirabot_smach_replicable', sm_main,
00684                                         '/estirabot_smach_replicable')
00685 
00686     sis.start()
00687 
00688     outcome = sm_main.execute()
00689 
00690     rospy.spin()
00691     sis.stop()
00692 
00693 if __name__ == "__main__":
00694     main()


estirabot_apps
Author(s): Jose Luis Rivero
autogenerated on Fri Dec 6 2013 23:20:59