$search
00001 #!/usr/bin/env python 00002 """ 00003 Description: 00004 This creates a concurrence with two states, one state, 'SET', waits three 00005 seconds before setting something in userdata, while another state 'GET' 00006 blocks while checking for thie userdata key, and only returns once it 00007 has been set. 00008 00009 Usage: 00010 $> ./concurrence.py 00011 00012 Output: 00013 [INFO] 1279226335.169182: Concurrence starting with userdata: 00014 [] 00015 [INFO] : >>> Waiting for data... 00016 [INFO] : >>> Waiting for data... 00017 [INFO] : >>> Waiting for data... 00018 [INFO] : >>> Waiting for data... 00019 [INFO] : >>> Waiting for data... 00020 [INFO] : >>> Waiting for data... 00021 [INFO] : >>> Set data: hello 00022 [INFO] : >>> GOT DATA! x = hello 00023 [INFO] : Concurrent Outcomes: {'SET': 'set_it', 'GET': 'got_it'} 00024 """ 00025 00026 import roslib; roslib.load_manifest('asmach_tutorials') 00027 import rospy 00028 import asmach as smach 00029 import smach_ros 00030 00031 # Define a state to set some user data 00032 class Setter(smach.State): 00033 def __init__(self, val): 00034 smach.State.__init__(self, outcomes = ['set_it'], output_keys = ['x']) 00035 self._val = val 00036 def execute(self, ud): 00037 # Delay a bit to make this clear 00038 rospy.sleep(3.0) 00039 # Set the data 00040 ud.x = self._val 00041 rospy.loginfo('>>> Set data: %s' % str(self._val)) 00042 return 'set_it' 00043 00044 # Define a state to get some user data 00045 class Getter(smach.State): 00046 def __init__(self): 00047 smach.State.__init__(self, outcomes = ['got_it'], input_keys = ['x']) 00048 def execute(self, ud): 00049 # Wait for data to appear 00050 while 'x' not in ud: 00051 rospy.loginfo('>>> Waiting for data...') 00052 rospy.sleep(0.5) 00053 rospy.loginfo('>>> GOT DATA! x = '+str(ud.x)) 00054 return 'got_it' 00055 00056 def main(): 00057 rospy.init_node('smach_example_concurrence') 00058 00059 # Create a SMACH state machine 00060 cc0 = smach.Concurrence( 00061 outcomes=['succeeded', 'aborted'], 00062 default_outcome='aborted', 00063 outcome_map = {'succeeded':{'SET':'set_it','GET':'got_it'}}) 00064 00065 # Open the container 00066 with cc0: 00067 # Add states to the container 00068 smach.Concurrence.add('SET', Setter(val='hello')) 00069 smach.Concurrence.add('GET', Getter()) 00070 00071 # Execute SMACH plan 00072 outcome = cc0.execute() 00073 00074 if __name__ == '__main__': 00075 main()