|
1 | 1 | import com.github.ekumen.rosjava_actionlib.*;
|
2 |
| -import static org.junit.Assert.assertEquals; |
| 2 | +import static org.junit.Assert.*; |
3 | 3 | import org.junit.Test;
|
| 4 | +import org.junit.Before; |
4 | 5 | import java.util.Vector;
|
| 6 | +import java.util.Arrays; |
5 | 7 | import actionlib_msgs.GoalStatus;
|
6 | 8 |
|
7 | 9 | public class TestClientStateMachine {
|
| 10 | + private ClientStateMachine subject; |
| 11 | + |
| 12 | + // Executes before each test. |
| 13 | + @Before |
| 14 | + public void setUp() { |
| 15 | + subject = new ClientStateMachine(); |
| 16 | + } |
| 17 | + |
| 18 | + @Test |
| 19 | + public void testGetState() { |
| 20 | + int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK; |
| 21 | + int actualState; |
| 22 | + subject.setState(expectedState); |
| 23 | + actualState = subject.getState(); |
| 24 | + assertEquals(expectedState, actualState); |
| 25 | + } |
| 26 | + |
8 | 27 | @Test
|
9 |
| - public void test1() { |
10 |
| - // test a full branch transition from goal ack to waiting for result |
11 |
| - int state; |
12 |
| - ClientStateMachine stateMachine = new ClientStateMachine(); |
13 |
| - |
14 |
| - // set initial state |
15 |
| - stateMachine.setState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK); |
16 |
| - // transition to next states |
17 |
| - stateMachine.transition(actionlib_msgs.GoalStatus.ACTIVE); |
18 |
| - assertEquals(ClientStateMachine.ClientStates.ACTIVE, stateMachine.getState()); |
19 |
| - stateMachine.transition(actionlib_msgs.GoalStatus.PREEMPTING); |
20 |
| - assertEquals(ClientStateMachine.ClientStates.PREEMPTING, stateMachine.getState()); |
21 |
| - stateMachine.transition(actionlib_msgs.GoalStatus.SUCCEEDED); |
22 |
| - assertEquals(ClientStateMachine.ClientStates.WAITING_FOR_RESULT, stateMachine.getState()); |
23 |
| - } |
24 |
| - |
25 |
| - @Test |
26 |
| - public void test2() { |
27 |
| - // test a vector of states transition for a skipped test |
28 |
| - int state; |
29 |
| - ClientStateMachine stateMachine = new ClientStateMachine(); |
30 |
| - |
31 |
| - // set initial state |
32 |
| - stateMachine.setState(ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK); |
33 |
| - // transition to next states |
34 |
| - stateMachine.transition(actionlib_msgs.GoalStatus.RECALLED); |
35 |
| - assertEquals(ClientStateMachine.ClientStates.WAITING_FOR_RESULT, stateMachine.getState()); |
| 28 | + public void testSetState() { |
| 29 | + int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK; |
| 30 | + assertEquals(subject.getState(), 0); |
| 31 | + subject.setState(expectedState); |
| 32 | + assertEquals(expectedState, subject.getState()); |
| 33 | + } |
| 34 | + |
| 35 | + @Test |
| 36 | + public void testUpdateStatusWhenStateIsNotDone() { |
| 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()); |
| 42 | + } |
| 43 | + |
| 44 | + @Test |
| 45 | + public void testUpdateStatusWhenStateIsDone() { |
| 46 | + subject.setState(ClientStateMachine.ClientStates.DONE); |
| 47 | + assertEquals(0, subject.getLatestGoalStatus()); |
| 48 | + subject.updateStatus(7); |
| 49 | + assertEquals(0, subject.getLatestGoalStatus()); |
| 50 | + } |
| 51 | + |
| 52 | + @Test |
| 53 | + public void testCancelOnCancellableStates() { |
| 54 | + checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK); |
| 55 | + checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.PENDING); |
| 56 | + checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.ACTIVE); |
| 57 | + } |
| 58 | + |
| 59 | + @Test |
| 60 | + public void testCancelOnNonCancellableStates() { |
| 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 | + |
| 71 | + private void checkCancelOnInitialCancellableState(int initialState) { |
| 72 | + subject.setState(initialState); |
| 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()); |
| 75 | + } |
| 76 | + |
| 77 | + |
| 78 | + private void checkCancelOnInitialNonCancellableState(int initialState) { |
| 79 | + subject.setState(initialState); |
| 80 | + assertFalse("Failed test on initial state " + initialState, subject.cancel()); |
| 81 | + assertEquals("Failed test on initial state " + initialState, initialState, subject.getState()); |
| 82 | + } |
| 83 | + |
| 84 | + @Test |
| 85 | + public void testResultReceivedWhileWaitingForResult() { |
| 86 | + subject.setState(ClientStateMachine.ClientStates.WAITING_FOR_RESULT); |
| 87 | + subject.resultReceived(); |
| 88 | + assertEquals(ClientStateMachine.ClientStates.DONE, subject.getState()); |
| 89 | + } |
| 90 | + |
| 91 | + @Test |
| 92 | + public void testResultReceivedWhileNotWaitingForResult() { |
| 93 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.INVALID_TRANSITION); |
| 94 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.NO_TRANSITION); |
| 95 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK); |
| 96 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.PENDING); |
| 97 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.ACTIVE); |
| 98 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK); |
| 99 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.RECALLING); |
| 100 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.PREEMPTING); |
| 101 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.DONE); |
| 102 | + checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.LOST); |
| 103 | + } |
| 104 | + |
| 105 | + private void checkResultReceivedWhileNotWaitingForResult(int state) { |
| 106 | + subject.setState(state); |
| 107 | + subject.resultReceived(); |
| 108 | + assertEquals("Failed test on initial state " + state, state, subject.getState()); |
| 109 | + } |
| 110 | + |
| 111 | + @Test |
| 112 | + public void testGetTrasition() { |
| 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); |
| 122 | + } |
| 123 | + |
| 124 | + private void checkGetTransition(int initialState, int goalStatus, Vector<Integer> expected) { |
| 125 | + subject.setState(initialState); |
| 126 | + Vector<Integer> output = subject.getTransition(goalStatus); |
| 127 | + assertEquals(expected, output); |
36 | 128 | }
|
37 | 129 | }
|
0 commit comments