Go to the documentation of this file.00001
00002 import traceback
00003 import smach
00004
00005 from smach.state_machine import StateMachine
00006
00007 from flexbe_core.core.event_state import EventState
00008 from flexbe_core.core.operatable_state_machine import OperatableStateMachine
00009 from flexbe_core.core.preemptable_state import PreemptableState
00010 from flexbe_core.core.priority_container import PriorityContainer
00011
00012
00013 class ConcurrencyContainer(EventState, OperatableStateMachine):
00014 """
00015 A state machine that can be operated.
00016 It synchronizes its current state with the mirror and supports some control mechanisms.
00017 """
00018
00019 def __init__(self, conditions=dict(), *args, **kwargs):
00020 super(ConcurrencyContainer, self).__init__(*args, **kwargs)
00021 self._conditions = conditions
00022 self._returned_outcomes = dict()
00023
00024 self.__execute = self.execute
00025 self.execute = self._concurrency_execute
00026
00027
00028 def _concurrency_execute(self, *args, **kwargs):
00029
00030 return OperatableStateMachine.execute(self, *args, **kwargs)
00031
00032
00033 def _build_msg(self, *args, **kwargs):
00034
00035 return OperatableStateMachine._build_msg(self, *args, **kwargs)
00036
00037
00038 def _update_once(self):
00039
00040 if self.preempt_requested() or PreemptableState.preempt:
00041 return self._preempted_name
00042
00043
00044 for state in self._ordered_states:
00045 if state.name in self._returned_outcomes.keys() and self._returned_outcomes[state.name] != self._loopback_name:
00046 continue
00047 if PriorityContainer.active_container is not None \
00048 and not PriorityContainer.active_container.startswith(state._get_path()) \
00049 and not state._get_path().startswith(PriorityContainer.active_container):
00050 if isinstance(state, EventState):
00051 state._notify_skipped()
00052 elif state._get_deep_state() is not None:
00053 state._get_deep_state()._notify_skipped()
00054 continue
00055 self._returned_outcomes[state.name] = self._execute_state(state)
00056
00057
00058
00059 outcome = self._loopback_name
00060 for item in self._conditions:
00061 (oc, cond) = item
00062 if all(self._returned_outcomes.has_key(sn) and self._returned_outcomes[sn] == o for sn,o in cond):
00063 outcome = oc
00064 break
00065
00066
00067 if outcome == self._loopback_name:
00068 return None
00069
00070 if outcome in self.get_registered_outcomes():
00071
00072 self.call_termination_cbs([s.name for s in self._ordered_states],outcome)
00073 self.on_exit(self.userdata, states = filter(lambda s: s.name not in self._returned_outcomes.keys() or self._returned_outcomes[s.name] == self._loopback_name, self._ordered_states))
00074 self._returned_outcomes = dict()
00075
00076
00077 self._parent._inner_sync_request = True
00078 self._current_state = None
00079
00080 return outcome
00081 else:
00082 raise smach.InvalidTransitionError("Outcome '%s' of state '%s' with transition target '%s' is neither a registered state nor a registered container outcome." %
00083 (outcome, self.name, outcome))
00084
00085 def _execute_state(self, state, force_exit=False):
00086 result = None
00087 try:
00088 ud = smach.Remapper(
00089 self.userdata,
00090 state.get_registered_input_keys(),
00091 state.get_registered_output_keys(),
00092 self._remappings[state.name])
00093 if force_exit:
00094 state._entering = True
00095 state.on_exit(ud)
00096 else:
00097 result = state.execute(ud)
00098
00099 except smach.InvalidUserCodeError as ex:
00100 smach.logerr("State '%s' failed to execute." % state.name)
00101 raise ex
00102 except:
00103 raise smach.InvalidUserCodeError("Could not execute state '%s' of type '%s': " %
00104 (state.name, state)
00105 + traceback.format_exc())
00106 return result
00107
00108
00109 def _notify_start(self):
00110 for state in self._ordered_states:
00111 if isinstance(state, EventState):
00112 state.on_start()
00113 if isinstance(state, OperatableStateMachine):
00114 state._notify_start()
00115
00116 def _enable_ros_control(self):
00117 state = self._ordered_states[0]
00118 if isinstance(state, EventState):
00119 state._enable_ros_control()
00120 if isinstance(state, OperatableStateMachine):
00121 state._enable_ros_control()
00122
00123 def _notify_stop(self):
00124 for state in self._ordered_states:
00125 if isinstance(state, EventState):
00126 state.on_stop()
00127 if isinstance(state, OperatableStateMachine):
00128 state._notify_stop()
00129 if state._is_controlled:
00130 state._disable_ros_control()
00131
00132 def _disable_ros_control(self):
00133 state = self._ordered_states[0]
00134 if isinstance(state, EventState):
00135 state._disable_ros_control()
00136 if isinstance(state, OperatableStateMachine):
00137 state._disable_ros_control()
00138
00139 def on_exit(self, userdata, states = None):
00140 for state in self._ordered_states if states is None else states:
00141 self._execute_state(state, force_exit=True)