5 from flexbe_core
import EventState, OperatableStateMachine
12 class ReturnInvalidOutcome(EventState):
15 super(ReturnInvalidOutcome, self).__init__(outcomes=[
'done'])
17 def execute(self, userdata):
20 sm = OperatableStateMachine(outcomes=[
'done'])
22 OperatableStateMachine.add(
'state', ReturnInvalidOutcome(), transitions={
'done':
'done'})
24 outcome = sm.execute(
None)
25 self.assertIsNone(outcome)
26 self.assertIsInstance(sm._last_exception, StateError)
29 class ReturnDone(EventState):
32 super(ReturnDone, self).__init__(outcomes=[
'done'])
34 def execute(self, userdata):
37 inner_sm = OperatableStateMachine(outcomes=[
'done'])
39 OperatableStateMachine.add(
'state', ReturnDone(), transitions={
'done':
'invalid'})
40 sm = OperatableStateMachine(outcomes=[
'done'])
42 OperatableStateMachine.add(
'inner', inner_sm, transitions={
'done':
'done'})
44 outcome = sm.execute(
None)
45 self.assertIsNone(outcome)
46 self.assertIsInstance(sm._last_exception, StateMachineError)
49 class AccessInvalidInput(EventState):
52 super(AccessInvalidInput, self).__init__(outcomes=[
'done'], input_keys=[
'input'])
54 def execute(self, userdata):
55 print(userdata.invalid)
58 sm = OperatableStateMachine(outcomes=[
'done'])
60 OperatableStateMachine.add(
'state', AccessInvalidInput(), transitions={
'done':
'done'})
62 outcome = sm.execute(
None)
63 self.assertIsNone(outcome)
64 self.assertIsInstance(sm._last_exception, UserDataError)
67 class SetInvalidOutput(EventState):
70 super(SetInvalidOutput, self).__init__(outcomes=[
'done'], output_keys=[
'output'])
72 def execute(self, userdata):
73 userdata.invalid =
False 76 sm = OperatableStateMachine(outcomes=[
'done'])
78 OperatableStateMachine.add(
'state', SetInvalidOutput(), transitions={
'done':
'done'})
80 outcome = sm.execute(
None)
81 self.assertIsNone(outcome)
82 self.assertIsInstance(sm._last_exception, UserDataError)
85 class AccessValidInput(EventState):
88 super(AccessValidInput, self).__init__(outcomes=[
'done'], input_keys=[
'missing'])
90 def execute(self, userdata):
91 print(userdata.missing)
94 sm = OperatableStateMachine(outcomes=[
'done'])
96 OperatableStateMachine.add(
'state', AccessValidInput(), transitions={
'done':
'done'})
98 outcome = sm.execute(
None)
99 self.assertIsNone(outcome)
100 self.assertIsInstance(sm._last_exception, UserDataError)
103 class ModifyInputKey(EventState):
106 super(ModifyInputKey, self).__init__(outcomes=[
'done'], input_keys=[
'only_input'])
108 def execute(self, userdata):
109 userdata.only_input[
'new'] =
'not_allowed' 112 sm = OperatableStateMachine(outcomes=[
'done'])
113 sm.userdata.only_input = {
'existing':
'is_allowed'}
115 OperatableStateMachine.add(
'state', ModifyInputKey(), transitions={
'done':
'done'})
117 outcome = sm.execute(
None)
118 self.assertIsNone(outcome)
119 self.assertIsInstance(sm._last_exception, UserDataError)
122 if __name__ ==
'__main__':
123 rospy.init_node(
'test_flexbe_exceptions')
125 rostest.rosrun(
'flexbe_core',
'test_flexbe_exceptions', TestExceptions)
def test_missing_userdata(self)
def test_invalid_userdata_output(self)
def test_invalid_userdata_input(self)
def test_invalid_outcome(self)
def test_modify_input_key(self)
def test_invalid_transition(self)