Skip to content

Commit 2a9ef92

Browse files
authored
Merge pull request #1 from ernestmc/add_tests
Add tests
2 parents 1027eb0 + 0b907b3 commit 2a9ef92

File tree

3 files changed

+141
-53
lines changed

3 files changed

+141
-53
lines changed

README.md

+7
Original file line numberDiff line numberDiff line change
@@ -92,3 +92,10 @@ roslaunch rosjava_actionlib server_demo.launch --screen
9292
```
9393

9494
Use Ctrl+C to stop the execution once it's finished.
95+
96+
97+
## Running unit tests
98+
```
99+
$ cd src/rosjava_actionlib/
100+
$ ./gradlew test
101+
```

src/rosjava_actionlib/rosjava_actionlib/src/main/java/com/github/ekumen/rosjava_actionlib/ClientStateMachine.java

+14-25
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
import actionlib_msgs.GoalStatus;
2121
import java.util.Vector;
2222
import java.util.Iterator;
23+
import java.util.ArrayList;
24+
import java.util.Arrays;
2325
import org.apache.commons.logging.Log;
2426
import org.apache.commons.logging.LogFactory;
2527

@@ -108,23 +110,7 @@ public synchronized void updateStatus(int status)
108110
{
109111
if (this.state != ClientStates.DONE)
110112
{
111-
/*status = this.goal.findStatus(statusArray); //_find_status_by_goal_id(statusArray, self.action_goal.goal_id.id);
112-
113-
// we haven't heard of the goal?
114-
if (status == 0)
115-
{
116-
if (this.state != ClientStates.WAITING_FOR_GOAL_ACK && this.state != ClientStates.WAITING_FOR_RESULT && this.state != ClientStates.DONE)
117-
{
118-
markAsLost();
119-
}
120-
return;
121-
}*/
122-
123113
this.latestGoalStatus = status;
124-
125-
// Determine the next state
126-
127-
//if (this.state
128114
}
129115
}
130116

@@ -453,16 +439,14 @@ public Vector<Integer> getTransition(int goalStatus)
453439
* @return True if the goal can be cancelled, false otherwise.
454440
*/
455441
public boolean cancel() {
456-
boolean ret = false;
457-
switch (state) {
458-
case ClientStates.WAITING_FOR_GOAL_ACK:
459-
case ClientStates.PENDING:
460-
case ClientStates.ACTIVE:
461-
state = ClientStates.WAITING_FOR_CANCEL_ACK;
462-
ret = true;
463-
break;
442+
ArrayList<Integer> cancellableStates = new ArrayList<>(Arrays.asList(ClientStates.WAITING_FOR_GOAL_ACK,
443+
ClientStates.PENDING, ClientStates.ACTIVE));
444+
boolean shouldCancel = cancellableStates.contains(state);
445+
446+
if (shouldCancel) {
447+
state = ClientStates.WAITING_FOR_CANCEL_ACK;
464448
}
465-
return ret;
449+
return shouldCancel;
466450
}
467451

468452
public void resultReceived() {
@@ -471,7 +455,12 @@ public void resultReceived() {
471455
}
472456
}
473457

458+
// TODO: implement method
474459
public void markAsLost()
475460
{
476461
}
462+
463+
public int getLatestGoalStatus() {
464+
return latestGoalStatus;
465+
}
477466
}
Original file line numberDiff line numberDiff line change
@@ -1,37 +1,129 @@
11
import com.github.ekumen.rosjava_actionlib.*;
2-
import static org.junit.Assert.assertEquals;
2+
import static org.junit.Assert.*;
33
import org.junit.Test;
4+
import org.junit.Before;
45
import java.util.Vector;
6+
import java.util.Arrays;
57
import actionlib_msgs.GoalStatus;
68

79
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+
827
@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);
36128
}
37129
}

0 commit comments

Comments
 (0)