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 from smach import StateMachine, CBState, Iterator
00010 from smach_ros import ServiceState
00011 from actionlib import *
00012 from actionlib.msg import *
00013 from std_msgs.msg import String
00014 from object_manipulation_msgs.msg import PickupAction,PickupGoal,PlaceAction,PlaceGoal
00015 from sensor_msgs.msg import PointCloud2, JointState
00016 from iri_deformable_analysis.srv import DoDeformableAnalysis, DoDeformableAnalysisRequest
00017 from estirabot_msgs.msg import PomdpGraspConfig
00018 from geometry_msgs.msg import Transform, PoseStamped, Pose
00019 from pprint import pprint
00020 from std_msgs.msg import Int8
00021
00022 from iri_common_smach.st_get_pcl import GetPCL
00023 from iri_common_smach.utils_msg import build_pose_stamped_msg, build_transform_msg
00024 from iri_common_smach.get_keystroke import GetKeyStroke
00025
00026 from estirabot_apps_base.utils_pomdp import PomdpConfigFactory
00027 from estirabot_apps_base.sm_move import SM_ESTIRABOT_GoHome
00028 from estirabot_apps_base.sm_deformable_analysis import SM_ESTIRABOT_DeformableAnalysis
00029 from estirabot_apps_base.sm_generate_grasp import SM_ESTIRABOT_GenerateGraspMsg
00030
00031 class PublishGraspID(smach.State):
00032 def __init__(self):
00033 smach.State.__init__(self, outcomes=['success','fail'],
00034 input_keys=['sm_pomdp_config'])
00035
00036 def execute(self, userdata):
00037 print "Publish grasp id"
00038
00039
00040 return 'success'
00041
00042 class HandlePomdpConfig(smach.State):
00043 def __init__(self):
00044 smach.State.__init__(self, outcomes=['ok'], input_keys=['algorithms','algorithms_index'],
00045 output_keys=['sm_pomdp_config','algorithms_index'])
00046
00047 def execute(self, userdata):
00048 magic_number = userdata.algorithms[userdata.algorithms_index]
00049
00050 factory = PomdpConfigFactory()
00051 userdata.sm_pomdp_config = factory.get_instance(magic_number)
00052
00053 pub = rospy.Publisher('/log/config_magic_number', Int8, None, False, True)
00054 pub.publish(magic_number)
00055 pprint("MAGIC NUMBER: " + str(magic_number))
00056
00057 userdata.algorithms_index = userdata.algorithms_index + 1
00058 pprint("INDEX: " + str(userdata.algorithms_index))
00059
00060 return 'ok'
00061
00062
00063 class PerformAnalysis(smach.State):
00064 def __init__(self):
00065 smach.State.__init__(self, outcomes=['success','fail','timeout'],
00066 input_keys=['pcl_RGB','sm_pomdp_config'],
00067 output_keys=['best_grasp_pose'])
00068
00069 def execute(self, userdata):
00070
00071 pub = rospy.Publisher('/log/pcl_table_scene', PointCloud2, None, False, True)
00072
00073
00074
00075 handler = rospy.ServiceProxy('/estirabot/skills/deformable_analysis/do_deformable_analysis',
00076 DoDeformableAnalysis)
00077
00078 analysis_request = DoDeformableAnalysisRequest()
00079 analysis_request.pcl_to_analyze = userdata.pcl_RGB
00080 analysis_request.fusion_criteria_id = userdata.sm_pomdp_config.best_pose_algorithm_id
00081
00082 try:
00083 response = handler(analysis_request)
00084
00085 if (not response):
00086 return 'fail'
00087
00088 except rospy.ServiceException, e:
00089 return 'timeout'
00090
00091 pose_st = response.deformable_analysis.graspability.best_grasp_pose
00092 userdata.best_grasp_pose = pose_st
00093 print("end analysis")
00094
00095 return 'success'
00096
00097 class CalculateGrasp(smach.State):
00098 def __init__(self):
00099 smach.State.__init__(self, outcomes=['success','fail','no_ik_solution','all_ik_fail'],
00100 input_keys=['best_grasp_pose','sm_pomdp_config'],
00101 output_keys=['sm_pomdp_config','grasp_goal'])
00102 self.tf_manager = TransformManager()
00103
00104 def execute(self, userdata):
00105
00106 pomdp_config = userdata.sm_pomdp_config
00107 grasp_pose_st = userdata.best_grasp_pose
00108
00109 rospy.set_param('/estirabot/skills/grasp/fingers_configuration', pomdp_config.fingers_grasp_configs)
00110
00111
00112
00113 grasp_pose_st_wam = self.tf_manager.transform_pose('wam_link0', grasp_pose_st)
00114
00115
00116 grasp_pose_st_wam.pose.orientation.x = 0
00117 grasp_pose_st_wam.pose.orientation.y = 0
00118 grasp_pose_st_wam.pose.orientation.z = 0
00119 grasp_pose_st_wam.pose.orientation.w = 1.0
00120
00121 pprint("Grasp original")
00122 pub = rospy.Publisher('/debug/grasp/original', PoseStamped, None, False, True)
00123 pub.publish(grasp_pose_st_wam)
00124
00125
00126 current_modifier = pomdp_config.approach_config.grasp_modifier_used
00127 pprint("Using grasp modifier number: " + str(current_modifier))
00128 real_grasp_st = PoseStamped()
00129 real_grasp_st.header = grasp_pose_st_wam.header
00130 real_grasp_st.pose = homogeneous_product_pose_transform(grasp_pose_st_wam.pose,
00131 pomdp_config.approach_config.grasp_modifiers[current_modifier])
00132 if (real_grasp_st.pose.position.z < -0.282):
00133 real_grasp_st.pose.position.z = -0.282
00134
00135 pprint("Grasp modifier applied")
00136 pub = rospy.Publisher('/debug/grasp/real', PoseStamped, None, False, True)
00137 pub.publish(real_grasp_st)
00138
00139
00140 pre_grasp_pose_st = PoseStamped()
00141 pre_grasp_pose_st.header = grasp_pose_st_wam.header
00142
00143 pre_grasp_pose_st.pose = homogeneous_product_pose_transform(real_grasp_st.pose,
00144 pomdp_config.approach_config.pre_grasp_modifier)
00145 pprint("PRE-Grasp modifier applied")
00146 pub = rospy.Publisher('/debug/grasp/pre_grasp', PoseStamped, None, False, True)
00147 pub.publish(pre_grasp_pose_st)
00148
00149
00150 pub_config = rospy.Publisher('/log/pomdp_config', PomdpGraspConfig, None, False, True)
00151 pub_config.publish(pomdp_config)
00152
00153
00154 try:
00155 joints_grasp = get_inverse_kinematics_from_pose(real_grasp_st.pose)
00156 joints_pre_grasp = get_inverse_kinematics_from_pose(pre_grasp_pose_st.pose)
00157
00158
00159 except rospy.ServiceException, e:
00160
00161 if (current_modifier < len(pomdp_config.approach_config.grasp_modifiers)-1):
00162
00163 pomdp_config.approach_config.grasp_modifier_used = pomdp_config.approach_config.grasp_modifier_used + 1
00164 pomdp_config.approach_config.pre_grasp_modifier
00165 return 'no_ik_solution'
00166 else:
00167
00168 pub = rospy.Publisher('/log/number_of_clothes', Int8, None, False, True)
00169 pub.publish(0)
00170 rospy.logerr("Inverse Kinematics has no solution")
00171 return 'all_ik_fail'
00172
00173
00174
00175
00176 userdata.grasp_goal = build_simple_pickup_goal(joints_grasp,
00177 joints_pre_grasp,
00178 pomdp_config.fingers_grasp_configs)
00179 return 'success'
00180
00181 def get_sm_grasp_goal_callback(userdata, default_goal):
00182 return userdata.sm_grasp_goal
00183
00184 def get_sm_place_goal_callback(userdata, default_goal):
00185 pose_stamped = PoseStamped()
00186 pose_stamped.header.frame_id = 'wam_link0'
00187 pose_stamped.header.stamp = rospy.Time.now()
00188 pose_stamped.pose = userdata.sm_pomdp_config.place_point
00189
00190 goal = PlaceGoal()
00191 goal.place_locations.append(userdata.sm_pomdp_config.place_point)
00192
00193 return goal
00194
00195 class InputResult(smach.State):
00196 def __init__(self):
00197 smach.State.__init__(self, outcomes=['ok'])
00198
00199 def execute(self, userdata):
00200 keyserver = GetKeyStroke()
00201 c = -1
00202 print "Press [0-5] for clothes grabbed:"
00203 while ((c < 0) or (c > 5)):
00204 c = keyserver()
00205 try:
00206 c = int(c)
00207 except ValueError:
00208 continue
00209
00210 print "Your value was: " + str(c)
00211 pub = rospy.Publisher('/log/number_of_clothes', Int8, None, False, True)
00212 pub.publish(c)
00213
00214 return 'ok'
00215
00216
00217 def construct_round_iterator_sm():
00218
00219 factory_home = SM_ESTIRABOT_GoHome()
00220 sm_home = factory_home.build_sm()
00221
00222 factory_analysis = SM_ESTIRABOT_DeformableAnalysis()
00223 sm_analysis = factory_analysis.build_sm()
00224
00225 factor_grasp = SM_ESTIRABOT_GenerateGraspMsg()
00226 sm_grasp_generation = factor_grasp.build_sm()
00227
00228
00229 sm_start_round = smach.StateMachine(outcomes=['success','aborted'],
00230 input_keys=['sm_pomdp_config'])
00231
00232 with sm_start_round:
00233 smach.StateMachine.add('PUBLISH_GRASP_ID', PublishGraspID(),
00234 transitions={'success' : 'MOVE_TO_HOME_POSITION',
00235 'fail' : 'aborted'})
00236
00237
00238 smach.StateMachine.add('MOVE_TO_HOME_POSITION', sm_home,
00239 transitions={'success' : 'success',
00240 'aborted' : 'aborted'})
00241
00242
00243 sm_calculate_grasp_point = smach.StateMachine(outcomes=['success','aborted','all_ik_fail'],
00244 input_keys=['sm_pomdp_config'],
00245 output_keys=['sm_grasp_goal'])
00246
00247 with sm_calculate_grasp_point:
00248
00249 smach.StateMachine.add('GET_KINECT_IMAGE',
00250 GetPCL("/estirabot/skills/pcl_distance_filtered"),
00251 transitions = {'success' : 'PERFORM_ANALISYS',
00252 'fail' : 'aborted'},
00253 remapping = {'pcl_RGB' : 'sm_pcl_output'})
00254 smach.StateMachine.add('PERFORM_ANALISYS', sm_analysis,
00255 transitions = {'success' : 'CALCULATE_GRASP',
00256 'fail' : 'aborted',
00257 'timeout' : 'aborted'},
00258 remapping = {'deformable_config' : 'sm_pomdp_config',
00259 'pcl_RGB' : 'sm_pcl_output',
00260 'best_grasp_pose' : 'sm_best_grasp_pose'})
00261 smach.StateMachine.add('CALCULATE_GRASP', sm_grasp_generation,
00262 transitions = {'success' : 'success',
00263 'fail' : 'aborted',
00264 'no_ik_solution' : 'CALCULATE_GRASP',
00265 'all_ik_fail' : 'all_ik_fail'},
00266 remapping = {'grasp_pose' : 'sm_best_grasp_pose',
00267 'pomdp_grasp_config' : 'sm_pomdp_config',
00268 'grasp_goal' : 'sm_grasp_goal'})
00269
00270
00271 sm_pick_and_lift = smach.StateMachine(outcomes=['success','aborted'],
00272 input_keys=['sm_grasp_goal'])
00273
00274 with sm_pick_and_lift:
00275
00276 smach.StateMachine.add('DO_GRASP',
00277 smach_ros.SimpleActionState('/estirabot/skills/grasp/pickup',
00278 PickupAction,
00279 goal_cb = get_sm_grasp_goal_callback,
00280 input_keys=['sm_grasp_goal']),
00281 {'succeeded': 'DO_LIFT',
00282 'preempted': 'aborted',
00283 'aborted' : 'aborted'})
00284
00285 smach.StateMachine.add('DO_LIFT', sm_home,
00286 transitions={'success' : 'success',
00287 'aborted' : 'aborted'})
00288
00289 sm_check_result = smach.StateMachine(outcomes=['success'])
00290
00291 with sm_check_result:
00292 smach.StateMachine.add('INPUT_RESULT', InputResult(),
00293 transitions = { 'ok' : 'success'})
00294
00295
00296 sm_drop = smach.StateMachine(outcomes=['success','aborted'],
00297 input_keys=['sm_pomdp_config'])
00298
00299 with sm_drop:
00300 smach.StateMachine.add('DO_PLACE',
00301 smach_ros.SimpleActionState('/estirabot/skills/iri_place/place',
00302 PlaceAction,
00303 goal_cb = get_sm_place_goal_callback,
00304 input_keys=['sm_pomdp_config']),
00305 {'succeeded': 'success',
00306 'preempted': 'aborted',
00307 'aborted' : 'aborted'})
00308
00309
00310 sm = StateMachine(outcomes = ['continue','aborted'],
00311 input_keys = ['algorithms','algorithms_index'],
00312 output_keys = ['algorithms','algorithms_index'])
00313 sm.userdata.rounds = 10
00314
00315 with sm:
00316 smach.StateMachine.add('CHOOSE_POMDP_CONFIG', HandlePomdpConfig(),
00317 transitions = {'ok':'ROUND_ITERATOR'})
00318
00319 round_iterator = Iterator(outcomes = ['succeeded','aborted'],
00320 input_keys = ['sm_pomdp_config'],
00321 it = range(0, sm.userdata.rounds),
00322 output_keys = ['sm_pomdp_config'],
00323 it_label = 'index',
00324 exhausted_outcome = 'succeeded')
00325 with round_iterator:
00326 container_sm = StateMachine(outcomes = ['succeeded','aborted','continue'],
00327 input_keys = ['sm_pomdp_config'],
00328 output_keys = ['sm_pomdp_config'])
00329 with container_sm:
00330
00331 smach.StateMachine.add('START_ROUND', sm_start_round,
00332 transitions={'success': 'CALCULATE_GRASP_POINT',
00333 'aborted': 'aborted'})
00334
00335 smach.StateMachine.add('CALCULATE_GRASP_POINT', sm_calculate_grasp_point,
00336 transitions={'success' : 'PICK_AND_LIFT',
00337 'aborted' : 'aborted',
00338 'all_ik_fail' : 'continue'})
00339
00340
00341 smach.StateMachine.add('PICK_AND_LIFT', sm_pick_and_lift,
00342 transitions={'success': 'CHECK_RESULT',
00343 'aborted': 'aborted' })
00344
00345 smach.StateMachine.add('CHECK_RESULT', sm_check_result,
00346 transitions = {'success': 'DROP'})
00347
00348
00349 smach.StateMachine.add('DROP', sm_drop,
00350 transitions = {'success': 'continue',
00351 'aborted': 'aborted'})
00352
00353
00354 Iterator.set_contained_state('CONTAINER_STATE',
00355 container_sm,
00356 loop_outcomes=['continue'])
00357
00358 StateMachine.add('ROUND_ITERATOR',round_iterator,
00359 {'succeeded':'continue',
00360 'aborted':'aborted'})
00361 return sm
00362
00363
00364
00365 def construct_alg_iterator_sm():
00366 sm = StateMachine(outcomes = ['succeeded','aborted'], output_keys = ['algorithms_index','algorithms'])
00367 sm.userdata.algorithms_index = 0
00368 sm.userdata.algorithms = [ 4 ]
00369
00370 sm.userdata.total_algs = len(sm.userdata.algorithms)
00371
00372 sm_container = construct_round_iterator_sm()
00373
00374 with sm:
00375 alg_iterator = Iterator(outcomes = ['succeeded','aborted'],
00376 input_keys = ['algorithms','algorithms_index'],
00377 it = range(0, sm.userdata.total_algs),
00378 output_keys = ['algorithms','algorithms_index'],
00379 it_label = 'index',
00380 exhausted_outcome = 'succeeded')
00381
00382 with alg_iterator:
00383 Iterator.set_contained_state('ALG_CONTAINER_STATE',
00384 sm_container,
00385 loop_outcomes=['continue'])
00386
00387 smach.StateMachine.add('ALGORITHM_ITERATOR', alg_iterator,
00388 {'succeeded':'succeeded',
00389 'aborted':'aborted'})
00390
00391 return sm
00392
00393 def main():
00394 rospy.init_node("pomdp_sm")
00395 sm_iterator = construct_alg_iterator_sm()
00396
00397
00398 sis = smach_ros.IntrospectionServer('estirabot_smach_replicable', sm_iterator,
00399 '/estirabot_smach_replicable')
00400
00401 sis.start()
00402
00403
00404 outcome = sm_iterator.execute()
00405
00406 rospy.spin()
00407 sis.stop()
00408
00409 if __name__ == "__main__":
00410 main()