test_exceptions.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import unittest
3 import rospy
4 
5 from flexbe_core import EventState, OperatableStateMachine
6 from flexbe_core.core.exceptions import StateError, StateMachineError, UserDataError
7 
8 
9 class TestExceptions(unittest.TestCase):
10 
12  class ReturnInvalidOutcome(EventState):
13 
14  def __init__(self):
15  super(ReturnInvalidOutcome, self).__init__(outcomes=['done'])
16 
17  def execute(self, userdata):
18  return 'invalid'
19 
20  sm = OperatableStateMachine(outcomes=['done'])
21  with sm:
22  OperatableStateMachine.add('state', ReturnInvalidOutcome(), transitions={'done': 'done'})
23 
24  outcome = sm.execute(None)
25  self.assertIsNone(outcome)
26  self.assertIsInstance(sm._last_exception, StateError)
27 
29  class ReturnDone(EventState):
30 
31  def __init__(self):
32  super(ReturnDone, self).__init__(outcomes=['done'])
33 
34  def execute(self, userdata):
35  return 'done'
36 
37  inner_sm = OperatableStateMachine(outcomes=['done'])
38  with inner_sm:
39  OperatableStateMachine.add('state', ReturnDone(), transitions={'done': 'invalid'})
40  sm = OperatableStateMachine(outcomes=['done'])
41  with sm:
42  OperatableStateMachine.add('inner', inner_sm, transitions={'done': 'done'})
43 
44  outcome = sm.execute(None)
45  self.assertIsNone(outcome)
46  self.assertIsInstance(sm._last_exception, StateMachineError)
47 
49  class AccessInvalidInput(EventState):
50 
51  def __init__(self):
52  super(AccessInvalidInput, self).__init__(outcomes=['done'], input_keys=['input'])
53 
54  def execute(self, userdata):
55  print(userdata.invalid)
56  return 'done'
57 
58  sm = OperatableStateMachine(outcomes=['done'])
59  with sm:
60  OperatableStateMachine.add('state', AccessInvalidInput(), transitions={'done': 'done'})
61 
62  outcome = sm.execute(None)
63  self.assertIsNone(outcome)
64  self.assertIsInstance(sm._last_exception, UserDataError)
65 
67  class SetInvalidOutput(EventState):
68 
69  def __init__(self):
70  super(SetInvalidOutput, self).__init__(outcomes=['done'], output_keys=['output'])
71 
72  def execute(self, userdata):
73  userdata.invalid = False
74  return 'done'
75 
76  sm = OperatableStateMachine(outcomes=['done'])
77  with sm:
78  OperatableStateMachine.add('state', SetInvalidOutput(), transitions={'done': 'done'})
79 
80  outcome = sm.execute(None)
81  self.assertIsNone(outcome)
82  self.assertIsInstance(sm._last_exception, UserDataError)
83 
85  class AccessValidInput(EventState):
86 
87  def __init__(self):
88  super(AccessValidInput, self).__init__(outcomes=['done'], input_keys=['missing'])
89 
90  def execute(self, userdata):
91  print(userdata.missing)
92  return 'done'
93 
94  sm = OperatableStateMachine(outcomes=['done'])
95  with sm:
96  OperatableStateMachine.add('state', AccessValidInput(), transitions={'done': 'done'})
97 
98  outcome = sm.execute(None)
99  self.assertIsNone(outcome)
100  self.assertIsInstance(sm._last_exception, UserDataError)
101 
103  class ModifyInputKey(EventState):
104 
105  def __init__(self):
106  super(ModifyInputKey, self).__init__(outcomes=['done'], input_keys=['only_input'])
107 
108  def execute(self, userdata):
109  userdata.only_input['new'] = 'not_allowed'
110  return 'done'
111 
112  sm = OperatableStateMachine(outcomes=['done'])
113  sm.userdata.only_input = {'existing': 'is_allowed'}
114  with sm:
115  OperatableStateMachine.add('state', ModifyInputKey(), transitions={'done': 'done'})
116 
117  outcome = sm.execute(None)
118  self.assertIsNone(outcome)
119  self.assertIsInstance(sm._last_exception, UserDataError)
120 
121 
122 if __name__ == '__main__':
123  rospy.init_node('test_flexbe_exceptions')
124  import rostest
125  rostest.rosrun('flexbe_core', 'test_flexbe_exceptions', TestExceptions)


flexbe_core
Author(s): Philipp Schillinger
autogenerated on Sun Dec 13 2020 04:01:39