Skip to content
Snippets Groups Projects
Commit 0b907b39 authored by Ernesto Corbellini's avatar Ernesto Corbellini
Browse files

Address @basicNew's comments.

parent ede0835c
No related branches found
No related tags found
No related merge requests found
...@@ -89,7 +89,7 @@ public class ClientStateMachine { ...@@ -89,7 +89,7 @@ public class ClientStateMachine {
} }
} }
public int latestGoalStatus; int latestGoalStatus;
int state; int state;
int nextState; int nextState;
private Log log = LogFactory.getLog(ActionClient.class); private Log log = LogFactory.getLog(ActionClient.class);
...@@ -439,17 +439,14 @@ public class ClientStateMachine { ...@@ -439,17 +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;
ArrayList<Integer> cancellableStates = new ArrayList<>(Arrays.asList(ClientStates.WAITING_FOR_GOAL_ACK, ArrayList<Integer> cancellableStates = new ArrayList<>(Arrays.asList(ClientStates.WAITING_FOR_GOAL_ACK,
ClientStates.PENDING, ClientStates.ACTIVE)); ClientStates.PENDING, ClientStates.ACTIVE));
boolean shouldCancel = cancellableStates.contains(state);
if (cancellableStates.contains(state)) { if (shouldCancel) {
state = ClientStates.WAITING_FOR_CANCEL_ACK; state = ClientStates.WAITING_FOR_CANCEL_ACK;
ret = true;
} else {
ret = false;
} }
return ret; return shouldCancel;
} }
public void resultReceived() { public void resultReceived() {
...@@ -462,4 +459,8 @@ public class ClientStateMachine { ...@@ -462,4 +459,8 @@ public class ClientStateMachine {
public void markAsLost() public void markAsLost()
{ {
} }
public int getLatestGoalStatus() {
return latestGoalStatus;
}
} }
...@@ -17,65 +17,36 @@ public class TestClientStateMachine { ...@@ -17,65 +17,36 @@ public class TestClientStateMachine {
@Test @Test
public void testGetState() { public void testGetState() {
// Setup
int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK; int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK;
int actualState; int actualState;
subject.setState(expectedState); subject.setState(expectedState);
// Optional: Precondition
// Exercise
actualState = subject.getState(); actualState = subject.getState();
// Assertion - Postcondition
assertEquals(expectedState, actualState); assertEquals(expectedState, actualState);
} }
@Test @Test
public void testSetState() { public void testSetState() {
// Setup
int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK; int expectedState = ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK;
// Optional: Precondition
assertEquals(subject.getState(), 0); assertEquals(subject.getState(), 0);
// Exercise
subject.setState(expectedState); subject.setState(expectedState);
// Assertion - Postcondition
assertEquals(expectedState, subject.getState()); assertEquals(expectedState, subject.getState());
} }
@Test @Test
public void testUpdateStatusWhenStateIsNotDone() { public void testUpdateStatusWhenStateIsNotDone() {
// Setup
int expectedStatus = 7; int expectedStatus = 7;
subject.setState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK); subject.setState(ClientStateMachine.ClientStates.WAITING_FOR_GOAL_ACK);
assertEquals(0, subject.getLatestGoalStatus());
// Optional: Precondition
assertEquals(0, subject.latestGoalStatus);
// Exercise
subject.updateStatus(expectedStatus); subject.updateStatus(expectedStatus);
assertEquals(expectedStatus, subject.getLatestGoalStatus());
// Assertion - Postcondition
assertEquals(expectedStatus, subject.latestGoalStatus);
} }
@Test @Test
public void testUpdateStatusWhenStateIsDone() { public void testUpdateStatusWhenStateIsDone() {
// Setup
subject.setState(ClientStateMachine.ClientStates.DONE); subject.setState(ClientStateMachine.ClientStates.DONE);
assertEquals(0, subject.getLatestGoalStatus());
// Optional: Precondition
assertEquals(0, subject.latestGoalStatus);
// Exercise
subject.updateStatus(7); subject.updateStatus(7);
assertEquals(0, subject.getLatestGoalStatus());
// Assertion - Postcondition
assertEquals(0, subject.latestGoalStatus);
} }
@Test @Test
...@@ -99,18 +70,14 @@ public class TestClientStateMachine { ...@@ -99,18 +70,14 @@ public class TestClientStateMachine {
private void checkCancelOnInitialCancellableState(int initialState) { private void checkCancelOnInitialCancellableState(int initialState) {
subject.setState(initialState); subject.setState(initialState);
assertTrue("Failed test on initial state " + initialState, subject.cancel()); assertTrue("Failed test on initial state " + initialState, subject.cancel());
assertEquals("Failed test on initial state " + initialState, ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK, subject.getState()); assertEquals("Failed test on initial state " + initialState, ClientStateMachine.ClientStates.WAITING_FOR_CANCEL_ACK, subject.getState());
} }
private void checkCancelOnInitialNonCancellableState(int initialState) { private void checkCancelOnInitialNonCancellableState(int initialState) {
subject.setState(initialState); subject.setState(initialState);
assertFalse("Failed test on initial state " + initialState, subject.cancel()); assertFalse("Failed test on initial state " + initialState, subject.cancel());
assertEquals("Failed test on initial state " + initialState, initialState, subject.getState()); assertEquals("Failed test on initial state " + initialState, initialState, subject.getState());
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment