Go to the documentation of this file.00001
00002 import rospy
00003
00004 from flexbe_core.proxy import ProxyPublisher, ProxySubscriberCached
00005 from flexbe_msgs.msg import CommandFeedback, OutcomeRequest
00006
00007 from flexbe_core.core.monitoring_state import MonitoringState
00008
00009
00010 class ManuallyTransitionableState(MonitoringState):
00011 """
00012 A state for that a desired outcome can be declared.
00013 If any outcome is declared, this outcome is forced.
00014 """
00015
00016 def __init__(self, *args, **kwargs):
00017 super(ManuallyTransitionableState, self).__init__(*args, **kwargs)
00018
00019 self._force_transition = False
00020
00021 self.__execute = self.execute
00022 self.execute = self._manually_transitionable_execute
00023
00024 self._feedback_topic = 'flexbe/command_feedback'
00025 self._transition_topic = 'flexbe/command/transition'
00026
00027 self._pub = ProxyPublisher()
00028 self._sub = ProxySubscriberCached()
00029
00030
00031 def _manually_transitionable_execute(self, *args, **kwargs):
00032 if self._is_controlled and self._sub.has_buffered(self._transition_topic):
00033 command_msg = self._sub.get_from_buffer(self._transition_topic)
00034 self._pub.publish(self._feedback_topic, CommandFeedback(command="transition", args=[command_msg.target, self.name]))
00035 if command_msg.target != self.name:
00036 rospy.logwarn("--> Requested outcome for state " + command_msg.target + " but active state is " + self.name)
00037 else:
00038 self._force_transition = True
00039 outcome = self._outcome_list[command_msg.outcome]
00040 rospy.loginfo("--> Manually triggered outcome " + outcome + " of state " + self.name)
00041 return outcome
00042
00043
00044 self._force_transition = False
00045 return self.__execute(*args, **kwargs)
00046
00047
00048 def _enable_ros_control(self):
00049 super(ManuallyTransitionableState, self)._enable_ros_control()
00050 self._pub.createPublisher(self._feedback_topic, CommandFeedback)
00051 self._sub.subscribe(self._transition_topic, OutcomeRequest)
00052 self._sub.enable_buffer(self._transition_topic)
00053
00054 def _disable_ros_control(self):
00055 super(ManuallyTransitionableState, self)._disable_ros_control()
00056 self._sub.unsubscribe_topic(self._transition_topic)