Skip to content

Commit

Permalink
Rename action state transitions (ros2#409)
Browse files Browse the repository at this point in the history
* Rename action state transitions

Now using active verbs.
Resolves ros2#399.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored Apr 16, 2019
1 parent edaa18a commit 26744b0
Show file tree
Hide file tree
Showing 6 changed files with 66 additions and 66 deletions.
8 changes: 4 additions & 4 deletions rcl_action/include/rcl_action/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,10 +97,10 @@ typedef int8_t rcl_action_goal_state_t;
typedef enum rcl_action_goal_event_t
{
GOAL_EVENT_EXECUTE = 0,
GOAL_EVENT_CANCEL,
GOAL_EVENT_SET_SUCCEEDED,
GOAL_EVENT_SET_ABORTED,
GOAL_EVENT_SET_CANCELED,
GOAL_EVENT_CANCEL_GOAL,
GOAL_EVENT_SUCCEED,
GOAL_EVENT_ABORT,
GOAL_EVENT_CANCELED,
GOAL_EVENT_NUM_EVENTS
} rcl_action_goal_event_t;

Expand Down
4 changes: 2 additions & 2 deletions rcl_action/src/rcl_action/goal_handle.c
Original file line number Diff line number Diff line change
Expand Up @@ -147,9 +147,9 @@ rcl_action_goal_handle_is_cancelable(const rcl_action_goal_handle_t * goal_handl
if (!rcl_action_goal_handle_is_valid(goal_handle)) {
return false; // error message is set
}
// Check if the state machine reports a cancel event is valid
// Check if the state machine reports a cancel goal event is valid
rcl_action_goal_state_t state = rcl_action_transition_goal_state(
goal_handle->impl->state, GOAL_EVENT_CANCEL);
goal_handle->impl->state, GOAL_EVENT_CANCEL_GOAL);
return GOAL_STATE_CANCELING == state;
}

Expand Down
30 changes: 15 additions & 15 deletions rcl_action/src/rcl_action/goal_state_machine.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,42 +33,42 @@ _execute_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t ev
}

rcl_action_goal_state_t
_cancel_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
_cancel_goal_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
{
if ((GOAL_STATE_ACCEPTED != state && GOAL_STATE_EXECUTING != state) ||
GOAL_EVENT_CANCEL != event)
GOAL_EVENT_CANCEL_GOAL != event)
{
return GOAL_STATE_UNKNOWN;
}
return GOAL_STATE_CANCELING;
}

rcl_action_goal_state_t
_set_succeeded_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
_succeed_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
{
if ((GOAL_STATE_EXECUTING != state && GOAL_STATE_CANCELING != state) ||
GOAL_EVENT_SET_SUCCEEDED != event)
GOAL_EVENT_SUCCEED != event)
{
return GOAL_STATE_UNKNOWN;
}
return GOAL_STATE_SUCCEEDED;
}

rcl_action_goal_state_t
_set_aborted_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
_abort_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
{
if ((GOAL_STATE_EXECUTING != state && GOAL_STATE_CANCELING != state) ||
GOAL_EVENT_SET_ABORTED != event)
GOAL_EVENT_ABORT != event)
{
return GOAL_STATE_UNKNOWN;
}
return GOAL_STATE_ABORTED;
}

rcl_action_goal_state_t
_set_canceled_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
_canceled_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event)
{
if (GOAL_STATE_CANCELING != state || GOAL_EVENT_SET_CANCELED != event) {
if (GOAL_STATE_CANCELING != state || GOAL_EVENT_CANCELED != event) {
return GOAL_STATE_UNKNOWN;
}
return GOAL_STATE_CANCELED;
Expand All @@ -79,17 +79,17 @@ static rcl_action_goal_event_handler
_goal_state_transition_map[GOAL_STATE_NUM_STATES][GOAL_EVENT_NUM_EVENTS] = {
[GOAL_STATE_ACCEPTED] = {
[GOAL_EVENT_EXECUTE] = _execute_event_handler,
[GOAL_EVENT_CANCEL] = _cancel_event_handler,
[GOAL_EVENT_CANCEL_GOAL] = _cancel_goal_event_handler,
},
[GOAL_STATE_EXECUTING] = {
[GOAL_EVENT_CANCEL] = _cancel_event_handler,
[GOAL_EVENT_SET_SUCCEEDED] = _set_succeeded_event_handler,
[GOAL_EVENT_SET_ABORTED] = _set_aborted_event_handler,
[GOAL_EVENT_CANCEL_GOAL] = _cancel_goal_event_handler,
[GOAL_EVENT_SUCCEED] = _succeed_event_handler,
[GOAL_EVENT_ABORT] = _abort_event_handler,
},
[GOAL_STATE_CANCELING] = {
[GOAL_EVENT_SET_SUCCEEDED] = _set_succeeded_event_handler,
[GOAL_EVENT_SET_ABORTED] = _set_aborted_event_handler,
[GOAL_EVENT_SET_CANCELED] = _set_canceled_event_handler,
[GOAL_EVENT_SUCCEED] = _succeed_event_handler,
[GOAL_EVENT_ABORT] = _abort_event_handler,
[GOAL_EVENT_CANCELED] = _canceled_event_handler,
},
};

Expand Down
2 changes: 1 addition & 1 deletion rcl_action/test/rcl_action/test_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ TEST_F(TestActionServer, test_action_clear_expired_goals)
handles.push_back(*goal_handle);
// Transition executing to aborted
ASSERT_EQ(RCL_RET_OK, rcl_action_update_goal_state(goal_handle, GOAL_EVENT_EXECUTE));
ASSERT_EQ(RCL_RET_OK, rcl_action_update_goal_state(goal_handle, GOAL_EVENT_SET_ABORTED));
ASSERT_EQ(RCL_RET_OK, rcl_action_update_goal_state(goal_handle, GOAL_EVENT_ABORT));
// Set time to something far in the future
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&this->clock, RCUTILS_S_TO_NS(99999)));
// Clear with valid arguments
Expand Down
42 changes: 21 additions & 21 deletions rcl_action/test/rcl_action/test_goal_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ using EventStateActiveCancelableTuple =
std::tuple<rcl_action_goal_event_t, rcl_action_goal_state_t, bool, bool>;
using StateTransitionSequence = std::vector<EventStateActiveCancelableTuple>;
const std::vector<std::string> event_strs = {
"EXECUTE", "CANCEL", "SET_SUCCEEDED", "SET_ABORTED", "SET_CANCELED"};
"EXECUTE", "CANCEL_GOAL", "SUCCEED", "ABORT", "CANCELED"};

class TestGoalHandleStateTransitionSequence
: public ::testing::TestWithParam<StateTransitionSequence>
Expand Down Expand Up @@ -242,39 +242,39 @@ TEST_P(TestGoalHandleStateTransitionSequence, test_goal_handle_state_transitions
const StateTransitionSequence valid_state_transition_sequences[] = {
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_CANCELED, GOAL_STATE_CANCELED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_CANCELED, GOAL_STATE_CANCELED, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_SUCCEEDED, GOAL_STATE_SUCCEEDED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SUCCEED, GOAL_STATE_SUCCEEDED, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_ABORTED, GOAL_STATE_ABORTED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_ABORT, GOAL_STATE_ABORTED, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_SET_SUCCEEDED, GOAL_STATE_SUCCEEDED, false, false),
std::make_tuple(GOAL_EVENT_SUCCEED, GOAL_STATE_SUCCEEDED, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_SET_ABORTED, GOAL_STATE_ABORTED, false, false),
std::make_tuple(GOAL_EVENT_ABORT, GOAL_STATE_ABORTED, false, false),
},
{
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_CANCELED, GOAL_STATE_CANCELED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_CANCELED, GOAL_STATE_CANCELED, false, false),
},
{
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_ABORTED, GOAL_STATE_ABORTED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_ABORT, GOAL_STATE_ABORTED, false, false),
},
// This is an odd case, but valid nonetheless
{
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SET_SUCCEEDED, GOAL_STATE_SUCCEEDED, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_SUCCEED, GOAL_STATE_SUCCEEDED, false, false),
},
};

Expand All @@ -287,26 +287,26 @@ INSTANTIATE_TEST_CASE_P(
const StateTransitionSequence invalid_state_transition_sequences[] = {
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_UNKNOWN, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_CANCEL, GOAL_STATE_UNKNOWN, false, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_CANCELING, true, false),
std::make_tuple(GOAL_EVENT_CANCEL_GOAL, GOAL_STATE_UNKNOWN, false, false),
},
{
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_EXECUTING, true, true),
std::make_tuple(GOAL_EVENT_EXECUTE, GOAL_STATE_UNKNOWN, false, false),
},
{
std::make_tuple(GOAL_EVENT_SET_CANCELED, GOAL_STATE_UNKNOWN, false, false),
std::make_tuple(GOAL_EVENT_CANCELED, GOAL_STATE_UNKNOWN, false, false),
},
{
std::make_tuple(GOAL_EVENT_SET_SUCCEEDED, GOAL_STATE_UNKNOWN, false, false),
std::make_tuple(GOAL_EVENT_SUCCEED, GOAL_STATE_UNKNOWN, false, false),
},
{
std::make_tuple(GOAL_EVENT_SET_ABORTED, GOAL_STATE_UNKNOWN, false, false),
std::make_tuple(GOAL_EVENT_ABORT, GOAL_STATE_UNKNOWN, false, false),
},
};

Expand Down
46 changes: 23 additions & 23 deletions rcl_action/test/rcl_action/test_goal_state_machine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,27 +24,27 @@ TEST(TestGoalStateMachine, test_valid_transitions)
EXPECT_EQ(GOAL_STATE_EXECUTING, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ACCEPTED,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_CANCELING, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_EXECUTING,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_CANCELING, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_EXECUTING,
GOAL_EVENT_SET_SUCCEEDED);
GOAL_EVENT_SUCCEED);
EXPECT_EQ(GOAL_STATE_SUCCEEDED, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_EXECUTING,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_ABORTED, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELING,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_CANCELED, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELING,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_ABORTED, state);
}

Expand All @@ -53,15 +53,15 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
// Invalid from ACCEPTED
rcl_action_goal_state_t state = rcl_action_transition_goal_state(
GOAL_STATE_ACCEPTED,
GOAL_EVENT_SET_SUCCEEDED);
GOAL_EVENT_SUCCEED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ACCEPTED,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ACCEPTED,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);

// Invalid from EXECUTING
Expand All @@ -71,7 +71,7 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_EXECUTING,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);

// Invalid from CANCELING
Expand All @@ -81,7 +81,7 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELING,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);

// Invalid from SUCCEEDED
Expand All @@ -91,19 +91,19 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_SUCCEEDED,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_SUCCEEDED,
GOAL_EVENT_SET_SUCCEEDED);
GOAL_EVENT_SUCCEED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_SUCCEEDED,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_SUCCEEDED,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);

// Invalid from ABORTED
Expand All @@ -113,19 +113,19 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ABORTED,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ABORTED,
GOAL_EVENT_SET_SUCCEEDED);
GOAL_EVENT_SUCCEED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ABORTED,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_ABORTED,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);

// Invalid from CANCELED
Expand All @@ -135,18 +135,18 @@ TEST(TestGoalStateMachine, test_invalid_transitions)
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELED,
GOAL_EVENT_CANCEL);
GOAL_EVENT_CANCEL_GOAL);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELED,
GOAL_EVENT_SET_SUCCEEDED);
GOAL_EVENT_SUCCEED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELED,
GOAL_EVENT_SET_ABORTED);
GOAL_EVENT_ABORT);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
state = rcl_action_transition_goal_state(
GOAL_STATE_CANCELED,
GOAL_EVENT_SET_CANCELED);
GOAL_EVENT_CANCELED);
EXPECT_EQ(GOAL_STATE_UNKNOWN, state);
}

0 comments on commit 26744b0

Please sign in to comment.