Skip to content
Snippets Groups Projects
Commit 2a9ef928 authored by Ernesto Corbellini's avatar Ernesto Corbellini Committed by GitHub
Browse files

Merge pull request #1 from ernestmc/add_tests

Add tests
parents 1027eb0c 0b907b39
No related branches found
No related tags found
No related merge requests found
...@@ -92,3 +92,10 @@ roslaunch rosjava_actionlib server_demo.launch --screen ...@@ -92,3 +92,10 @@ roslaunch rosjava_actionlib server_demo.launch --screen
``` ```
Use Ctrl+C to stop the execution once it's finished. Use Ctrl+C to stop the execution once it's finished.
## Running unit tests
```
$ cd src/rosjava_actionlib/
$ ./gradlew test
```
...@@ -20,6 +20,8 @@ import java.lang.Exception; ...@@ -20,6 +20,8 @@ import java.lang.Exception;
import actionlib_msgs.GoalStatus; import actionlib_msgs.GoalStatus;
import java.util.Vector; import java.util.Vector;
import java.util.Iterator; import java.util.Iterator;
import java.util.ArrayList;
import java.util.Arrays;
import org.apache.commons.logging.Log; import org.apache.commons.logging.Log;
import org.apache.commons.logging.LogFactory; import org.apache.commons.logging.LogFactory;
...@@ -108,23 +110,7 @@ public class ClientStateMachine { ...@@ -108,23 +110,7 @@ public class ClientStateMachine {
{ {
if (this.state != ClientStates.DONE) if (this.state != ClientStates.DONE)
{ {
/*status = this.goal.findStatus(statusArray); //_find_status_by_goal_id(statusArray, self.action_goal.goal_id.id);
// we haven't heard of the goal?
if (status == 0)
{
if (this.state != ClientStates.WAITING_FOR_GOAL_ACK && this.state != ClientStates.WAITING_FOR_RESULT && this.state != ClientStates.DONE)
{
markAsLost();
}
return;
}*/
this.latestGoalStatus = status; this.latestGoalStatus = status;
// Determine the next state
//if (this.state
} }
} }
...@@ -453,16 +439,14 @@ public class ClientStateMachine { ...@@ -453,16 +439,14 @@ public class ClientStateMachine {
* @return True if the goal can be cancelled, false otherwise. * @return True if the goal can be cancelled, false otherwise.
*/ */
public boolean cancel() { public boolean cancel() {
boolean ret = false; ArrayList<Integer> cancellableStates = new ArrayList<>(Arrays.asList(ClientStates.WAITING_FOR_GOAL_ACK,
switch (state) { ClientStates.PENDING, ClientStates.ACTIVE));
case ClientStates.WAITING_FOR_GOAL_ACK: boolean shouldCancel = cancellableStates.contains(state);
case ClientStates.PENDING:
case ClientStates.ACTIVE: if (shouldCancel) {
state = ClientStates.WAITING_FOR_CANCEL_ACK; state = ClientStates.WAITING_FOR_CANCEL_ACK;
ret = true;
break;
} }
return ret; return shouldCancel;
} }
public void resultReceived() { public void resultReceived() {
...@@ -471,7 +455,12 @@ public class ClientStateMachine { ...@@ -471,7 +455,12 @@ public class ClientStateMachine {
} }
} }
// TODO: implement method
public void markAsLost() public void markAsLost()
{ {
} }
public int getLatestGoalStatus() {
return latestGoalStatus;
}
} }
import com.github.ekumen.rosjava_actionlib.*; import com.github.ekumen.rosjava_actionlib.*;
import static org.junit.Assert.assertEquals; import static org.junit.Assert.*;
import org.junit.Test; import org.junit.Test;
import org.junit.Before;
import java.util.Vector; import java.util.Vector;
import java.util.Arrays;
import actionlib_msgs.GoalStatus; import actionlib_msgs.GoalStatus;
public class TestClientStateMachine { public class TestClientStateMachine {
private ClientStateMachine subject;
// Executes before each test.
@Before
public void setUp() {
subject = new ClientStateMachine();
}
@Test
public void testGetState() {
int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK;
int actualState;
subject.setState(expectedState);
actualState = subject.getState();
assertEquals(expectedState, actualState);
}
@Test @Test
public void test1() { public void testSetState() {
// test a full branch transition from goal ack to waiting for result int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK;
int state; assertEquals(subject.getState(), 0);
ClientStateMachine stateMachine = new ClientStateMachine(); subject.setState(expectedState);
assertEquals(expectedState, subject.getState());
// set initial state }
stateMachine.setState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK);
// transition to next states @Test
stateMachine.transition(actionlib_msgs.GoalStatus.ACTIVE); public void testUpdateStatusWhenStateIsNotDone() {
assertEquals(ClientStateMachine.ClientStates.ACTIVE, stateMachine.getState()); int expectedStatus = 7;
stateMachine.transition(actionlib_msgs.GoalStatus.PREEMPTING); subject.setState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK);
assertEquals(ClientStateMachine.ClientStates.PREEMPTING, stateMachine.getState()); assertEquals(0, subject.getLatestGoalStatus());
stateMachine.transition(actionlib_msgs.GoalStatus.SUCCEEDED); subject.updateStatus(expectedStatus);
assertEquals(ClientStateMachine.ClientStates.WAITING_FOR_RESULT, stateMachine.getState()); assertEquals(expectedStatus, subject.getLatestGoalStatus());
} }
@Test @Test
public void test2() { public void testUpdateStatusWhenStateIsDone() {
// test a vector of states transition for a skipped test subject.setState(ClientStateMachine.ClientStates.DONE);
int state; assertEquals(0, subject.getLatestGoalStatus());
ClientStateMachine stateMachine = new ClientStateMachine(); subject.updateStatus(7);
assertEquals(0, subject.getLatestGoalStatus());
// set initial state }
stateMachine.setState(ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK);
// transition to next states @Test
stateMachine.transition(actionlib_msgs.GoalStatus.RECALLED); public void testCancelOnCancellableStates() {
assertEquals(ClientStateMachine.ClientStates.WAITING_FOR_RESULT, stateMachine.getState()); checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK);
checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.PENDING);
checkCancelOnInitialCancellableState(ClientStateMachine.ClientStates.ACTIVE);
}
@Test
public void testCancelOnNonCancellableStates() {
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.INVALID_TRANSITION);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.NO_TRANSITION);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.WAITING_FOR_RESULT);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.RECALLING);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.PREEMPTING);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.DONE);
checkCancelOnInitialNonCancellableState(ClientStateMachine.ClientStates.LOST);
}
private void checkCancelOnInitialCancellableState(int initialState) {
subject.setState(initialState);
assertTrue("Failed test on initial state " + initialState, subject.cancel());
assertEquals("Failed test on initial state " + initialState, ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK, subject.getState());
}
private void checkCancelOnInitialNonCancellableState(int initialState) {
subject.setState(initialState);
assertFalse("Failed test on initial state " + initialState, subject.cancel());
assertEquals("Failed test on initial state " + initialState, initialState, subject.getState());
}
@Test
public void testResultReceivedWhileWaitingForResult() {
subject.setState(ClientStateMachine.ClientStates.WAITING_FOR_RESULT);
subject.resultReceived();
assertEquals(ClientStateMachine.ClientStates.DONE, subject.getState());
}
@Test
public void testResultReceivedWhileNotWaitingForResult() {
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.INVALID_TRANSITION);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.NO_TRANSITION);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.PENDING);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.ACTIVE);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.RECALLING);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.PREEMPTING);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.DONE);
checkResultReceivedWhileNotWaitingForResult(ClientStateMachine.ClientStates.LOST);
}
private void checkResultReceivedWhileNotWaitingForResult(int state) {
subject.setState(state);
subject.resultReceived();
assertEquals("Failed test on initial state " + state, state, subject.getState());
}
@Test
public void testGetTrasition() {
Vector<Integer> expected;
expected = new Vector<>(Arrays.asList(ClientStateMachine.ClientStates.PENDING));
checkGetTransition(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK,
actionlib_msgs.GoalStatus.PENDING, expected);
expected = new Vector<>(Arrays.asList(ClientStateMachine.ClientStates.PENDING,
ClientStateMachine.ClientStates.WAITING_FOR_RESULT));
checkGetTransition(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK,
actionlib_msgs.GoalStatus.REJECTED, expected);
}
private void checkGetTransition(int initialState, int goalStatus, Vector<Integer> expected) {
subject.setState(initialState);
Vector<Integer> output = subject.getTransition(goalStatus);
assertEquals(expected, output);
} }
} }
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment