manually_transitionable_state.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 
4 from flexbe_core.proxy import ProxyPublisher, ProxySubscriberCached
5 from flexbe_msgs.msg import CommandFeedback, OutcomeRequest
6 
7 from flexbe_core.core.monitoring_state import MonitoringState
8 
9 
11  """
12  A state for that a desired outcome can be declared.
13  If any outcome is declared, this outcome is forced.
14  """
15 
16  def __init__(self, *args, **kwargs):
17  super(ManuallyTransitionableState, self).__init__(*args, **kwargs)
18 
19  self._force_transition = False
20 
21  self.__execute = self.execute
23 
24  self._feedback_topic = 'flexbe/command_feedback'
25  self._transition_topic = 'flexbe/command/transition'
26 
27  self._pub = ProxyPublisher()
28  self._sub = ProxySubscriberCached()
29 
30 
31  def _manually_transitionable_execute(self, *args, **kwargs):
32  if self._is_controlled and self._sub.has_buffered(self._transition_topic):
33  command_msg = self._sub.get_from_buffer(self._transition_topic)
34  self._pub.publish(self._feedback_topic, CommandFeedback(command="transition", args=[command_msg.target, self.name]))
35  if command_msg.target != self.name:
36  rospy.logwarn("--> Requested outcome for state " + command_msg.target + " but active state is " + self.name)
37  else:
38  self._force_transition = True
39  outcome = self._outcome_list[command_msg.outcome]
40  rospy.loginfo("--> Manually triggered outcome " + outcome + " of state " + self.name)
41  return outcome
42 
43  # return the normal outcome
44  self._force_transition = False
45  return self.__execute(*args, **kwargs)
46 
47 
49  super(ManuallyTransitionableState, self)._enable_ros_control()
50  self._pub.createPublisher(self._feedback_topic, CommandFeedback)
51  self._sub.subscribe(self._transition_topic, OutcomeRequest)
52  self._sub.enable_buffer(self._transition_topic)
53 
55  super(ManuallyTransitionableState, self)._disable_ros_control()
56  self._sub.unsubscribe_topic(self._transition_topic)


flexbe_core
Author(s): Philipp Schillinger
autogenerated on Wed Jun 5 2019 21:51:59