sm_cleaning_old.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 
00004 import roslib; roslib.load_manifest('iri_clean_board')
00005 import rospy
00006 import smach
00007 import smach_ros
00008 
00009 from smach_ros import SimpleActionState
00010 from smach_ros import ServiceState
00011 
00012 from actionlib import *
00013 from actionlib.msg import *
00014 from iri_clean_board.msg import *
00015 from iri_clean_board.srv import *
00016 from estirabot_msgs.msg import *
00017 from estirabot_msgs.srv import *
00018 #from iri_wam_common_msgs.srv import *
00019 #from geometry_msgs.msg import *
00020 #import tf
00021 
00022 # define state Foo
00023 class NeedInfo(smach.State):
00024         def __init__(self):
00025                 smach.State.__init__(self, outcomes=['next','failed'])
00026                 self.counter = 0
00027 
00028         def execute(self, userdata):
00029                 rospy.loginfo('Executing state NeedInfo')
00030                 return 'next'
00031 
00032 
00033 # define state Bar
00034 class Planning(smach.State):
00035         def __init__(self):
00036                 smach.State.__init__(self, outcomes=['next','finish','get_info','failed'],
00037                                      input_keys=['image_segm','pointcloud_segm','plane_coefficients'],
00038                                      output_keys=['poses','plane_coefficients','poses_2d_coordinates','secondary_arm'])
00039         
00040 
00041         def execute(self, userdata):
00042                 if userdata.pointcloud_segm.height == 0:
00043                         rospy.loginfo('Pointcloud isn\'t available yet')
00044                         return 'get_info'
00045                 
00046                 rospy.loginfo('Executing state Planning')
00047                 rospy.wait_for_service('/iri_clean_plan/cleaning_plan/get_cleaning_plan')
00048                 try:
00049                         get_cleaning_plan = rospy.ServiceProxy('/iri_clean_plan/cleaning_plan/get_cleaning_plan', PlanSrv)
00050                         resp = get_cleaning_plan(userdata.pointcloud_segm, userdata.image_segm, userdata.plane_coefficients)
00051                         if resp.is_clean:
00052                                 return 'finish'
00053                         elif not resp.movement:
00054                                 return 'get_info'
00055                         else:
00056                                 userdata.poses = resp.poses
00057                                 userdata.plane_coefficients = resp.plane_coefficients
00058                                 userdata.poses_2d_coordinates = resp.poses_2d_coordinates
00059                                 userdata.secondary_arm = resp.secondary_arm
00060                                 return 'next'
00061                 except rospy.ServiceException, e:
00062                         print "Service call failed: %s"%e
00063                         return 'failed'
00064 
00065 
00066 
00067 class MoveArm(smach.State):
00068         def __init__(self):
00069                 smach.State.__init__(self, outcomes=['next','failed'],
00070                                         input_keys=['poses','plane_coefficients','poses_2d_coordinates','secondary_arm'])
00071 
00072         def execute(self, userdata):
00073                 rospy.loginfo('Waiting for service')
00074                 rospy.wait_for_service('/iri_clean_plan/arm_movements_by_pose/clean_movement')
00075                 try:
00076                         move_arm = rospy.ServiceProxy('/iri_clean_plan/arm_movements_by_pose/clean_movement', ArmMovementsPosesSrv)
00077                         resp = move_arm(userdata.poses, userdata.secondary_arm, userdata.plane_coefficients, 1)
00078                         if resp.success:
00079                                 print 'Executing service success'
00080                                 return 'next'
00081                         else:
00082                                 # publish unreachable points
00083                                 pub = rospy.Publisher('/iri_clean_perception/get_board_information/unreachable_position', ImagePoint)
00084                                 for idx in resp.too_far_points_indexes:
00085                                         pub.publish(userdata.poses_2d_coordinates[idx])
00086                                 print 'Executing service failed. Maybe IK.'
00087                                 return 'next'
00088                 except rospy.ServiceException, e:
00089                         print "Service call failed: %s"%e
00090                         return 'failed'
00091 
00092 
00093 class MoveArmBase(smach.State):
00094         def __init__(self):
00095                 smach.State.__init__(self, outcomes=['next','failed'])
00096 
00097         def execute(self, userdata):
00098                 rospy.loginfo('Waiting for service')
00099                 rospy.wait_for_service('/iri_clean_plan/arm_movements_by_pose/clean_movement')
00100                 try:
00101                         # make a empty service message
00102                         clean_mov = ArmMovementsPosesSrv()
00103                         clean_mov.movement_type = 0
00104                         clean_mov.poses = [];
00105                         move_arm = rospy.ServiceProxy('/iri_clean_plan/arm_movements_by_pose/clean_movement', ArmMovementsPosesSrv)
00106                         resp = move_arm(clean_mov.poses, [], [], 0)
00107                         if resp.success:
00108                                 print 'Executing service success'
00109                                 return 'next'
00110                         else:
00111                                 print 'Executing service  failed'
00112                                 return 'next'
00113                 except rospy.ServiceException, e:
00114                         print "Service call failed: %s"%e
00115                         return 'failed'
00116 
00117 
00118 
00119 def main():
00120         rospy.init_node('smach_example_state_machine')
00121 
00122         # Create a SMACH state machine
00123         sm = smach.StateMachine(outcomes=['finishOk','failedVision','failedPlanning','failedMoveArm'])
00124 
00125         # Open the container
00126         with sm:
00127                 # Add states to the container
00128                 smach.StateMachine.add('NeedInfo', NeedInfo(),
00129                                 transitions={'next':'GetInfoAction', 
00130                                                 'failed':'failedVision'},)
00131                                                 
00132                 smach.StateMachine.add('GetInfoAction', 
00133                                 #SimpleActionState('/iri_clean_perception/get_board_information/get_board_info',
00134                                 #                 GetBoardInfoAction,
00135                                 #                 result_slots=['segmented_image', 
00136                                 #                               'pointcloud',
00137                                 #                               'plane_coefficients']),
00138                                                   #server_wait_timeout=rospy.Duration(10.0)),
00139                                 ServiceState('/iri_clean_perception/get_board_information/get_board_info_srv',
00140                                                         BoardInfo,
00141                                                         response_slots=['segmented_image', 
00142                                                                         'pointcloud',
00143                                                                         'plane_coefficients']),
00144                                 transitions={'succeeded':'Planning',
00145                                                 'preempted':'failedVision',
00146                                                 'aborted':'failedVision'},
00147                                 remapping={'segmented_image':'image_segm',
00148                                                 'pointcloud':'pointcloud_segm',
00149                                                 'plane_coefficients':'plane_coefficients'})
00150                                                 
00151                 smach.StateMachine.add('Planning', Planning(), 
00152                                 transitions={'next':'MoveArm', 
00153                                                 #'finish':'finishOk', 
00154                                                 'finish':'MoveArmBase',
00155                                                 'get_info':'NeedInfo', 
00156                                                 'failed':'failedPlanning'})
00157                 smach.StateMachine.add('MoveArm', MoveArm(), 
00158                                 transitions={'next':'NeedInfo', 
00159                                                 'failed':'failedMoveArm'})
00160                 smach.StateMachine.add('MoveArmBase', MoveArmBase(), 
00161                                 transitions={'next':'NeedInfo', 
00162                                                 'failed':'failedMoveArm'})
00163 
00164         # Execute SMACH plan
00165         outcome = sm.execute()
00166 
00167 
00168 
00169 if __name__ == '__main__':
00170         main()


iri_clean_board
Author(s): David Martinez
autogenerated on Fri Dec 6 2013 23:52:37