sm_move.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 
00008 from smach import CBState
00009 from iri_common_smach.utils_msg          import build_pose_stamped_msg
00010 from iri_wam_smach.sm_wam_move_from_pose import SM_WAM_MoveFromPose
00011 
00012 class SM_ESTIRABOT_GoHome():
00013     """
00014     """
00015     def __init__(self):
00016         self.sm = smach.StateMachine(outcomes=['success','aborted'])
00017 
00018     @smach.cb_interface(input_keys = [],
00019                         output_keys= ['pose_st'],
00020                         outcomes   = ['finish'])
00021     def home_pose_cb(ud):
00022 #ud.pose_st = build_pose_stamped_msg('/wam_link0',0.5, 0, 0.13, 0.0, 1.0, 0.0, 0.0)
00023         ud.pose_st = build_pose_stamped_msg('/wam_link0',0.5, 0, 0, 0.0, 1.0, 0.0, 0.0)
00024 
00025         return 'finish'
00026 
00027     def build_sm(self):
00028         f_move = SM_WAM_MoveFromPose('/estirabot/wam_wrapper/joints_move',
00029                                       '/estirabot/iri_wam_tcp_ik/get_wam_ik')
00030         sm_move = f_move.build_sm()
00031 
00032         with self.sm:
00033             smach.StateMachine.add('DEFINE_HOME_POSE', CBState(self.home_pose_cb),
00034                               transitions  = {'finish'  : 'MOVE_TO_HOME'},
00035                               remapping    = {'pose_st' : 'sm_pose_st'})
00036 
00037             smach.StateMachine.add('MOVE_TO_HOME', sm_move,
00038                               transitions  = {'success'  : 'success',
00039                                               'aborted'  : 'aborted',
00040                                               'no_kinematic_solution' : 'aborted'},
00041                               remapping    = {'pose_st' : 'sm_pose_st'})
00042         return self.sm


estirabot_apps_base
Author(s): Jose Luis Rivero
autogenerated on Fri Dec 6 2013 21:07:07