7
7
import actionlib_msgs .GoalStatus ;
8
8
9
9
public class TestClientStateMachine {
10
- private ClientStateMachine subject ;
11
-
12
- // Executes before each test.
10
+ private ClientStateMachine subject ;
11
+
12
+ // Executes before each test.
13
13
@ Before
14
14
public void setUp () {
15
15
subject = new ClientStateMachine ();
16
16
}
17
-
17
+
18
18
@ Test
19
19
public void testGetState () {
20
- // Setup
21
- int expectedState = ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ;
22
- int actualState ;
23
-
24
- subject .setState (expectedState );
25
-
26
- // Optional: Precondition
27
-
28
- // Exercise
29
- actualState = subject .getState ();
30
-
31
- // Assertion - Postcondition
32
- assertEquals (expectedState , actualState );
20
+ int expectedState = ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ;
21
+ int actualState ;
22
+ subject .setState (expectedState );
23
+ actualState = subject .getState ();
24
+ assertEquals (expectedState , actualState );
33
25
}
34
-
26
+
35
27
@ Test
36
28
public void testSetState () {
37
- // Setup
38
- int expectedState = ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ;
39
-
40
- // Optional: Precondition
41
- assertEquals (subject .getState (), 0 );
42
-
43
- // Exercise
44
- subject .setState (expectedState );
45
-
46
- // Assertion - Postcondition
47
- assertEquals (expectedState , subject .getState ());
29
+ int expectedState = ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ;
30
+ assertEquals (subject .getState (), 0 );
31
+ subject .setState (expectedState );
32
+ assertEquals (expectedState , subject .getState ());
48
33
}
49
-
34
+
50
35
@ Test
51
36
public void testUpdateStatusWhenStateIsNotDone () {
52
- // Setup
53
- int expectedStatus = 7 ;
54
- subject .setState (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK );
55
-
56
- // Optional: Precondition
57
- assertEquals (0 , subject .latestGoalStatus );
58
-
59
- // Exercise
60
- subject .updateStatus (expectedStatus );
61
-
62
- // Assertion - Postcondition
63
- assertEquals (expectedStatus , subject .latestGoalStatus );
37
+ int expectedStatus = 7 ;
38
+ subject .setState (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK );
39
+ assertEquals (0 , subject .getLatestGoalStatus ());
40
+ subject .updateStatus (expectedStatus );
41
+ assertEquals (expectedStatus , subject .getLatestGoalStatus ());
64
42
}
65
-
43
+
66
44
@ Test
67
45
public void testUpdateStatusWhenStateIsDone () {
68
- // Setup
69
- subject .setState (ClientStateMachine .ClientStates .DONE );
70
-
71
- // Optional: Precondition
72
- assertEquals (0 , subject .latestGoalStatus );
73
-
74
- // Exercise
75
- subject .updateStatus (7 );
76
-
77
- // Assertion - Postcondition
78
- assertEquals (0 , subject .latestGoalStatus );
46
+ subject .setState (ClientStateMachine .ClientStates .DONE );
47
+ assertEquals (0 , subject .getLatestGoalStatus ());
48
+ subject .updateStatus (7 );
49
+ assertEquals (0 , subject .getLatestGoalStatus ());
79
50
}
80
-
51
+
81
52
@ Test
82
53
public void testCancelOnCancellableStates () {
83
- checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK );
84
- checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .PENDING );
85
- checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .ACTIVE );
54
+ checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK );
55
+ checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .PENDING );
56
+ checkCancelOnInitialCancellableState (ClientStateMachine .ClientStates .ACTIVE );
86
57
}
87
-
58
+
88
59
@ Test
89
60
public void testCancelOnNonCancellableStates () {
90
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .INVALID_TRANSITION );
91
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .NO_TRANSITION );
92
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_RESULT );
93
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_CANCEL_ACK );
94
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .RECALLING );
95
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .PREEMPTING );
96
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .DONE );
97
- checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .LOST );
98
- }
99
-
61
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .INVALID_TRANSITION );
62
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .NO_TRANSITION );
63
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_RESULT );
64
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .WAITING_FOR_CANCEL_ACK );
65
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .RECALLING );
66
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .PREEMPTING );
67
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .DONE );
68
+ checkCancelOnInitialNonCancellableState (ClientStateMachine .ClientStates .LOST );
69
+ }
70
+
100
71
private void checkCancelOnInitialCancellableState (int initialState ) {
101
72
subject .setState (initialState );
102
-
103
- assertTrue ("Failed test on initial state " + initialState , subject .cancel ());
104
-
105
- assertEquals ("Failed test on initial state " + initialState , ClientStateMachine .ClientStates .WAITING_FOR_CANCEL_ACK , subject .getState ());
73
+ assertTrue ("Failed test on initial state " + initialState , subject .cancel ());
74
+ assertEquals ("Failed test on initial state " + initialState , ClientStateMachine .ClientStates .WAITING_FOR_CANCEL_ACK , subject .getState ());
106
75
}
107
76
108
77
109
78
private void checkCancelOnInitialNonCancellableState (int initialState ) {
110
79
subject .setState (initialState );
111
-
112
- assertFalse ("Failed test on initial state " + initialState , subject .cancel ());
113
-
114
- assertEquals ("Failed test on initial state " + initialState , initialState , subject .getState ());
80
+ assertFalse ("Failed test on initial state " + initialState , subject .cancel ());
81
+ assertEquals ("Failed test on initial state " + initialState , initialState , subject .getState ());
115
82
}
116
-
83
+
117
84
@ Test
118
85
public void testResultReceivedWhileWaitingForResult () {
119
86
subject .setState (ClientStateMachine .ClientStates .WAITING_FOR_RESULT );
120
87
subject .resultReceived ();
121
88
assertEquals (ClientStateMachine .ClientStates .DONE , subject .getState ());
122
89
}
123
-
90
+
124
91
@ Test
125
92
public void testResultReceivedWhileNotWaitingForResult () {
126
93
checkResultReceivedWhileNotWaitingForResult (ClientStateMachine .ClientStates .INVALID_TRANSITION );
@@ -134,26 +101,26 @@ public void testResultReceivedWhileNotWaitingForResult() {
134
101
checkResultReceivedWhileNotWaitingForResult (ClientStateMachine .ClientStates .DONE );
135
102
checkResultReceivedWhileNotWaitingForResult (ClientStateMachine .ClientStates .LOST );
136
103
}
137
-
104
+
138
105
private void checkResultReceivedWhileNotWaitingForResult (int state ) {
139
106
subject .setState (state );
140
107
subject .resultReceived ();
141
- assertEquals ("Failed test on initial state " + state , state , subject .getState ());
108
+ assertEquals ("Failed test on initial state " + state , state , subject .getState ());
142
109
}
143
-
110
+
144
111
@ Test
145
112
public void testGetTrasition () {
146
- Vector <Integer > expected ;
147
- expected = new Vector <>(Arrays .asList (ClientStateMachine .ClientStates .PENDING ));
148
- checkGetTransition (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ,
149
- actionlib_msgs .GoalStatus .PENDING , expected );
150
-
151
- expected = new Vector <>(Arrays .asList (ClientStateMachine .ClientStates .PENDING ,
152
- ClientStateMachine .ClientStates .WAITING_FOR_RESULT ));
153
- checkGetTransition (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ,
154
- actionlib_msgs .GoalStatus .REJECTED , expected );
113
+ Vector <Integer > expected ;
114
+ expected = new Vector <>(Arrays .asList (ClientStateMachine .ClientStates .PENDING ));
115
+ checkGetTransition (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ,
116
+ actionlib_msgs .GoalStatus .PENDING , expected );
117
+
118
+ expected = new Vector <>(Arrays .asList (ClientStateMachine .ClientStates .PENDING ,
119
+ ClientStateMachine .ClientStates .WAITING_FOR_RESULT ));
120
+ checkGetTransition (ClientStateMachine .ClientStates .WAITING_FOR_GOAL_ACK ,
121
+ actionlib_msgs .GoalStatus .REJECTED , expected );
155
122
}
156
-
123
+
157
124
private void checkGetTransition (int initialState , int goalStatus , Vector <Integer > expected ) {
158
125
subject .setState (initialState );
159
126
Vector <Integer > output = subject .getTransition (goalStatus );
0 commit comments