operatable_state_machine.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import zlib
3 from flexbe_core.core.user_data import UserData
4 from flexbe_core.logger import Logger
5 from flexbe_core.state_logger import StateLogger
6 from flexbe_core.core.operatable_state import OperatableState
7 
8 from flexbe_msgs.msg import Container, ContainerStructure, BehaviorSync, CommandFeedback
9 from std_msgs.msg import Empty, UInt8, Int32
10 
11 from flexbe_core.core.preemptable_state_machine import PreemptableStateMachine
12 
13 
15  """
16  A state machine that can be operated.
17  It synchronizes its current state with the mirror and supports some control mechanisms.
18  """
19 
20  autonomy_level = 3
21 
22  def __init__(self, *args, **kwargs):
23  super(OperatableStateMachine, self).__init__(*args, **kwargs)
24  self.id = None
25  self._autonomy = {}
26  self._inner_sync_request = False
27  self._last_exception = None
28 
29  # construction
30 
31  @staticmethod
32  def add(label, state, transitions, autonomy=None, remapping=None):
33  """
34  Add a state to the opened state machine.
35 
36  @type label: string
37  @param label: The label of the state being added.
38 
39  @param state: An instance of a class implementing the L{State} interface.
40 
41  @param transitions: A dictionary mapping state outcomes to other state
42  labels or container outcomes.
43 
44  @param autonomy: A dictionary mapping state outcomes to their required
45  autonomy level
46 
47  @param remapping: A dictionary mapping local userdata keys to userdata
48  keys in the container.
49  """
50  self = OperatableStateMachine.get_opened_container()
51  PreemptableStateMachine.add(label, state, transitions, remapping)
52  self._autonomy[label] = autonomy
53 
55  """
56  Creates a message to describe the structure of this state machine.
57  """
58  structure_msg = ContainerStructure()
59  container_msg = self._add_to_structure_msg(structure_msg)
60  container_msg.outcomes = self.outcomes
61  structure_msg.behavior_id = self.id
62  return structure_msg
63 
64  def _add_to_structure_msg(self, structure_msg):
65  """
66  Adds this state machine and all children to the structure message.
67 
68  @type structure_msg: ContainerStructure
69  @param structure_msg: The message that will finally contain the structure message.
70  """
71  # add self to message
72  container_msg = Container()
73  container_msg.path = self.path
74  container_msg.children = [state.name for state in self._states]
75  structure_msg.containers.append(container_msg)
76  # add children to message
77  for state in self._states:
78  # create and add children
79  if isinstance(state, OperatableStateMachine):
80  state_msg = state._add_to_structure_msg(structure_msg)
81  else:
82  state_msg = Container(path=state.path)
83  structure_msg.containers.append(state_msg)
84  # complete structure info for children
85  state_msg.outcomes = state.outcomes
86  state_msg.transitions = [self._transitions[state.name][outcome] for outcome in state.outcomes]
87  state_msg.autonomy = [self._autonomy[state.name][outcome] for outcome in state.outcomes]
88  return container_msg
89 
90  # execution
91 
93  # catch any exception and keep state active to let operator intervene
94  try:
95  outcome = super(OperatableStateMachine, self)._execute_current_state()
96  self._last_exception = None
97  except Exception as e:
98  outcome = None
99  self._last_exception = e
100  Logger.logerr('Failed to execute state %s:\n%s' % (self.current_state_label, str(e)))
101  # provide explicit sync as back-up functionality
102  # should be used only if there is no other choice
103  # since it requires additional 8 byte + header update bandwith and time to restart mirror
104  if self._inner_sync_request and self.get_deep_state() is not None:
105  self._inner_sync_request = False
106  if self.id is None:
107  self.parent._inner_sync_request = True
108  else:
109  msg = BehaviorSync()
110  msg.behavior_id = self.id
111  msg.current_state_checksum = zlib.adler32(self.get_deep_state().path.encode()) & 0x7fffffff
112  self._pub.publish('flexbe/mirror/sync', msg)
113  return outcome
114 
115  def is_transition_allowed(self, label, outcome):
116  return self._autonomy[label].get(outcome, -1) < OperatableStateMachine.autonomy_level
117 
118  def get_required_autonomy(self, outcome):
119  return self._autonomy[self.current_state_label][outcome]
120 
121  def destroy(self):
122  self._notify_stop()
123  self._disable_ros_control()
124  self._sub.unsubscribe_topic('flexbe/command/autonomy')
125  self._sub.unsubscribe_topic('flexbe/command/sync')
126  self._sub.unsubscribe_topic('flexbe/command/attach')
127  self._sub.unsubscribe_topic('flexbe/request_mirror_structure')
128  StateLogger.shutdown()
129 
130  def confirm(self, name, id):
131  """
132  Confirms the state machine and triggers the creation of the structural message.
133  It is mandatory to call this function at the top-level state machine
134  between building it and starting its execution.
135 
136  @type name: string
137  @param name: The name of this state machine to identify it.
138  """
139  self.set_name(name)
140  self.id = id
141 
142  # Update mirror with currently active state (high bandwidth mode)
143  self._pub.createPublisher('flexbe/mirror/sync', BehaviorSync)
144  # Sends the current structure to the mirror
145  self._pub.createPublisher('flexbe/mirror/structure', ContainerStructure)
146  # Gives feedback about executed commands to the GUI
147  self._pub.createPublisher('flexbe/command_feedback', CommandFeedback)
148 
149  self._sub.subscribe('flexbe/command/autonomy', UInt8, self._set_autonomy_level)
150  self._sub.subscribe('flexbe/command/sync', Empty, self._sync_callback)
151  self._sub.subscribe('flexbe/command/attach', UInt8, self._attach_callback)
152  self._sub.subscribe('flexbe/request_mirror_structure', Int32, self._mirror_structure_callback)
153 
154  StateLogger.initialize(name)
155  StateLogger.log('flexbe.initialize', None, behavior=name, autonomy=OperatableStateMachine.autonomy_level)
156  if OperatableStateMachine.autonomy_level != 255:
157  self._enable_ros_control()
158 
159  self.wait(seconds=0.2) # no clean way to wait for publisher to be ready...
160  self._notify_start()
161 
162  # operator callbacks
163 
164  def _set_autonomy_level(self, msg):
165  """ Sets the current autonomy level. """
166  if OperatableStateMachine.autonomy_level != msg.data:
167  Logger.localinfo('--> Autonomy changed to %d' % msg.data)
168  if msg.data < 0:
169  self.preempt()
170  else:
171  OperatableStateMachine.autonomy_level = msg.data
172  self._pub.publish('flexbe/command_feedback', CommandFeedback(command="autonomy", args=[]))
173 
174  def _sync_callback(self, msg):
175  Logger.localinfo("--> Synchronization requested...")
176  msg = BehaviorSync()
177  msg.behavior_id = self.id
178  # make sure we are already executing
179  self.wait(condition=lambda: self.get_deep_state() is not None)
180  msg.current_state_checksum = zlib.adler32(self.get_deep_state().path.encode()) & 0x7fffffff
181  self._pub.publish('flexbe/mirror/sync', msg)
182  self._pub.publish('flexbe/command_feedback', CommandFeedback(command="sync", args=[]))
183  Logger.localinfo("<-- Sent synchronization message for mirror.")
184 
185  def _attach_callback(self, msg):
186  Logger.localinfo("--> Enabling control...")
187  # set autonomy level
188  OperatableStateMachine.autonomy_level = msg.data
189  # enable control of states
190  self._enable_ros_control()
191  self._inner_sync_request = True
192  # send command feedback
193  cfb = CommandFeedback(command="attach")
194  cfb.args.append(self.name)
195  self._pub.publish('flexbe/command_feedback', cfb)
196  Logger.localinfo("<-- Sent attach confirm.")
197 
199  Logger.localinfo("--> Creating behavior structure for mirror...")
200  self._pub.publish('flexbe/mirror/structure', self._build_structure_msg())
201  Logger.localinfo("<-- Sent behavior structure for mirror.")
202  # enable control of states since a mirror is listening
203  self._enable_ros_control()
204 
205  # handle state events
206 
207  def _notify_start(self):
208  for state in self._states:
209  if isinstance(state, OperatableState):
210  state.on_start()
211  if isinstance(state, OperatableStateMachine):
212  state._notify_start()
213 
214  def _notify_stop(self):
215  for state in self._states:
216  if isinstance(state, OperatableState):
217  state.on_stop()
218  if isinstance(state, OperatableStateMachine):
219  state._notify_stop()
220  if state._is_controlled:
221  state._disable_ros_control()
222 
223  def on_exit(self, userdata):
224  if self._current_state is not None:
225  ud = UserData(reference=self.userdata, input_keys=self._current_state.input_keys,
226  output_keys=self._current_state.output_keys,
227  remap=self._remappings[self._current_state.name])
228  self._current_state._entering = True
229  self._current_state.on_exit(ud)
230  self._current_state = None
flexbe_core.core.user_data.UserData
Definition: user_data.py:6
flexbe_core.core.user_data
Definition: user_data.py:1
flexbe_core.core.operatable_state_machine.OperatableStateMachine._notify_stop
def _notify_stop(self)
Definition: operatable_state_machine.py:214
flexbe_core.core.lockable_state_machine.LockableStateMachine.get_deep_state
def get_deep_state(self)
Definition: lockable_state_machine.py:18
flexbe_core.state_logger
Definition: state_logger.py:1
flexbe_core.core.operatable_state_machine.OperatableStateMachine._inner_sync_request
_inner_sync_request
Definition: operatable_state_machine.py:26
flexbe_core.core.operatable_state_machine.OperatableStateMachine._sync_callback
def _sync_callback(self, msg)
Definition: operatable_state_machine.py:174
flexbe_core.core.state_machine.StateMachine._states
_states
Definition: state_machine.py:13
flexbe_core.core.operatable_state_machine.OperatableStateMachine._build_structure_msg
def _build_structure_msg(self)
Definition: operatable_state_machine.py:54
flexbe_core.core.operatable_state_machine.OperatableStateMachine._notify_start
def _notify_start(self)
Definition: operatable_state_machine.py:207
flexbe_core.core.operatable_state_machine.OperatableStateMachine.on_exit
def on_exit(self, userdata)
Definition: operatable_state_machine.py:223
flexbe_core.core.state_machine.StateMachine.userdata
def userdata(self)
Definition: state_machine.py:105
flexbe_core.core.ros_state_machine.RosStateMachine._disable_ros_control
def _disable_ros_control(self)
Definition: ros_state_machine.py:35
flexbe_core.core.operatable_state_machine.OperatableStateMachine._add_to_structure_msg
def _add_to_structure_msg(self, structure_msg)
Definition: operatable_state_machine.py:64
flexbe_core.core.state_machine.StateMachine._remappings
_remappings
Definition: state_machine.py:16
flexbe_core.logger
Definition: logger.py:1
flexbe_core.core.operatable_state_machine.OperatableStateMachine.is_transition_allowed
def is_transition_allowed(self, label, outcome)
Definition: operatable_state_machine.py:115
flexbe_core.core.operatable_state_machine.OperatableStateMachine._execute_current_state
def _execute_current_state(self)
Definition: operatable_state_machine.py:92
flexbe_core.core.operatable_state_machine.OperatableStateMachine.get_required_autonomy
def get_required_autonomy(self, outcome)
Definition: operatable_state_machine.py:118
flexbe_core.core.ros_state_machine.RosStateMachine._enable_ros_control
def _enable_ros_control(self)
Definition: ros_state_machine.py:30
flexbe_core.core.state.State.outcomes
def outcomes(self)
Definition: state.py:35
flexbe_core.core.operatable_state_machine.OperatableStateMachine._attach_callback
def _attach_callback(self, msg)
Definition: operatable_state_machine.py:185
flexbe_core.core.operatable_state_machine.OperatableStateMachine
Definition: operatable_state_machine.py:14
flexbe_core.core.ros_state_machine.RosStateMachine.wait
def wait(self, seconds=None, condition=None)
Definition: ros_state_machine.py:20
flexbe_core.core.state.State.path
def path(self)
Definition: state.py:69
flexbe_core.core.lockable_state_machine.LockableStateMachine._current_state
_current_state
Definition: lockable_state_machine.py:47
flexbe_core.core.preemptable_state_machine.PreemptableStateMachine._sub
_sub
Definition: preemptable_state_machine.py:22
flexbe_core.core.operatable_state_machine.OperatableStateMachine.destroy
def destroy(self)
Definition: operatable_state_machine.py:121
flexbe_core.core.state.State.parent
def parent(self)
Definition: state.py:59
flexbe_core.core.operatable_state_machine.OperatableStateMachine.__init__
def __init__(self, *args, **kwargs)
Definition: operatable_state_machine.py:22
flexbe_core.core.operatable_state_machine.OperatableStateMachine.add
def add(label, state, transitions, autonomy=None, remapping=None)
Definition: operatable_state_machine.py:32
flexbe_core.core.preemptable_state_machine.PreemptableStateMachine
Definition: preemptable_state_machine.py:10
flexbe_core.core.state_machine.StateMachine._transitions
_transitions
Definition: state_machine.py:15
flexbe_core.core.operatable_state
Definition: operatable_state.py:1
flexbe_core.core.operatable_state_machine.OperatableStateMachine._last_exception
_last_exception
Definition: operatable_state_machine.py:27
flexbe_core.core.state_machine.StateMachine.current_state_label
def current_state_label(self)
Definition: state_machine.py:116
flexbe_core.core.operatable_state_machine.OperatableStateMachine._mirror_structure_callback
def _mirror_structure_callback(self, msg)
Definition: operatable_state_machine.py:198
flexbe_core.core.operatable_state_machine.OperatableStateMachine.id
id
Definition: operatable_state_machine.py:24
flexbe_core.core.operatable_state_machine.OperatableStateMachine.confirm
def confirm(self, name, id)
Definition: operatable_state_machine.py:130
flexbe_core.core.state.State.set_name
def set_name(self, value)
Definition: state.py:52
flexbe_core.core.ros_state_machine.RosStateMachine._pub
_pub
Definition: ros_state_machine.py:17
flexbe_core.core.preemptable_state_machine
Definition: preemptable_state_machine.py:1
flexbe_core.core.state.State.name
def name(self)
Definition: state.py:49
flexbe_core.core.operatable_state_machine.OperatableStateMachine._set_autonomy_level
def _set_autonomy_level(self, msg)
Definition: operatable_state_machine.py:164
flexbe_core.core.operatable_state_machine.OperatableStateMachine._autonomy
_autonomy
Definition: operatable_state_machine.py:25


flexbe_core
Author(s): Philipp Schillinger
autogenerated on Fri Jul 21 2023 02:26:05