Go to the documentation of this file.00001 
00002 
00003 import roslib; roslib.load_manifest('flexbe_mirror')
00004 import rospy
00005 from rospy.exceptions import ROSInterruptException
00006 from flexbe_core import EventState, JumpableStateMachine
00007 
00008 from flexbe_core.proxy import ProxyPublisher, ProxySubscriberCached
00009 from std_msgs.msg import String, UInt8
00010 
00011 '''
00012 Created on 07.05.2013
00013 
00014 @author: Philipp Schillinger
00015 '''
00016 
00017 class MirrorState(EventState):
00018     '''
00019     This state will display its possible outcomes as buttons in the GUI and is designed in a way to be created dynamically.
00020     '''
00021 
00022 
00023     def __init__(self, target_name, target_path, given_outcomes, outcome_autonomy):
00024         '''
00025         Constructor
00026         '''
00027         super(MirrorState, self).__init__(outcomes=given_outcomes)
00028         self._rate = rospy.Rate(100)
00029         self._given_outcomes = given_outcomes
00030         self._outcome_autonomy = outcome_autonomy
00031         self._target_name = target_name
00032         self._target_path = target_path
00033         
00034         self._outcome_topic = 'flexbe/mirror/outcome'
00035 
00036         self._pub = ProxyPublisher() 
00037         self._sub = ProxySubscriberCached({self._outcome_topic: UInt8})
00038         
00039         
00040     def execute(self, userdata):
00041         '''
00042         Execute this state
00043         '''
00044         if JumpableStateMachine.refresh:
00045             JumpableStateMachine.refresh = False
00046             self.on_enter(userdata)
00047 
00048         if self._sub.has_buffered(self._outcome_topic):
00049             msg = self._sub.get_from_buffer(self._outcome_topic)
00050             if msg.data < len(self._given_outcomes):
00051                 rospy.loginfo("State update: %s > %s", self._target_name, self._given_outcomes[msg.data])
00052                 return self._given_outcomes[msg.data]
00053 
00054         try:
00055             self._rate.sleep()
00056         except ROSInterruptException:
00057             print 'Interrupted mirror sleep.'
00058     
00059     
00060     def on_enter(self, userdata):
00061         
00062         self._pub.publish('flexbe/behavior_update', String("/" + "/".join(self._target_path.split("/")[1:])))
00063     
00064     
00065     
00066     
00067     
00068     
00069