Go to the documentation of this file.00001
00002
00003 from smach.state_machine import StateMachine
00004
00005 from .preemptable_state_machine import PreemptableStateMachine
00006 from flexbe_core.core.loopback_state import LoopbackState
00007 import rospy
00008
00009
00010 class SilentStateMachine(PreemptableStateMachine):
00011 """
00012 A state machine that runs in background and does not report any transition.
00013 """
00014
00015 def __init__(self, *args, **kwargs):
00016 super(SilentStateMachine, self).__init__(*args, **kwargs)
00017 self.name = None
00018 self.transitions = None
00019 self.autonomy = None
00020 self._parent = None
00021
00022 @staticmethod
00023 def add(label, state, transitions = None, autonomy = None, remapping = None):
00024 """
00025 Add a state to the opened state machine.
00026
00027 @type label: string
00028 @param label: The label of the state being added.
00029
00030 @param state: An instance of a class implementing the L{State} interface.
00031
00032 @param transitions: A dictionary mapping state outcomes to other state
00033 labels or container outcomes.
00034
00035 @param autonomy: A dictionary mapping state outcomes to their required
00036 autonomy level. Not relevant for this class.
00037
00038 @param remapping: A dictrionary mapping local userdata keys to userdata
00039 keys in the container.
00040 """
00041 self = StateMachine._currently_opened_container()
00042
00043
00044 if isinstance(state, LoopbackState):
00045 transitions[LoopbackState._loopback_name] = label
00046
00047 StateMachine.add(label, state, transitions, remapping)
00048
00049 state.name = label
00050 state.transitions = transitions
00051 state.autonomy = None
00052 state._parent = self
00053 state._mute = True
00054
00055 def destroy(self):
00056 pass