From 81b28ec8108538fbf88b0e1603dbe76566721ad0 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Fri, 29 Mar 2019 18:08:18 -0700 Subject: [PATCH] Rename action state transitions Now using active verbs. Resolves #399. Signed-off-by: Jacob Perron --- rcl_action/include/rcl_action/types.h | 6 ++-- .../src/rcl_action/goal_state_machine.c | 22 ++++++------ .../test/rcl_action/test_action_server.cpp | 2 +- .../test/rcl_action/test_goal_handle.cpp | 24 ++++++------- .../rcl_action/test_goal_state_machine.cpp | 34 +++++++++---------- 5 files changed, 44 insertions(+), 44 deletions(-) diff --git a/rcl_action/include/rcl_action/types.h b/rcl_action/include/rcl_action/types.h index d87b067d1f..f1762f75ea 100644 --- a/rcl_action/include/rcl_action/types.h +++ b/rcl_action/include/rcl_action/types.h @@ -98,9 +98,9 @@ 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_SUCCEED, + GOAL_EVENT_ABORT, + GOAL_EVENT_CANCEL, GOAL_EVENT_NUM_EVENTS } rcl_action_goal_event_t; diff --git a/rcl_action/src/rcl_action/goal_state_machine.c b/rcl_action/src/rcl_action/goal_state_machine.c index cfb38fd716..5c3c007182 100644 --- a/rcl_action/src/rcl_action/goal_state_machine.c +++ b/rcl_action/src/rcl_action/goal_state_machine.c @@ -44,10 +44,10 @@ _cancel_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t eve } 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; } @@ -55,10 +55,10 @@ _set_succeeded_event_handler(rcl_action_goal_state_t state, rcl_action_goal_even } 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; } @@ -66,9 +66,9 @@ _set_aborted_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_ } rcl_action_goal_state_t -_set_canceled_event_handler(rcl_action_goal_state_t state, rcl_action_goal_event_t event) +_cancel_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_CANCEL != event) { return GOAL_STATE_UNKNOWN; } return GOAL_STATE_CANCELED; @@ -83,13 +83,13 @@ static rcl_action_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_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_CANCEL] = _cancel_event_handler, }, }; diff --git a/rcl_action/test/rcl_action/test_action_server.cpp b/rcl_action/test/rcl_action/test_action_server.cpp index f92c6feeb2..0bd6c54877 100644 --- a/rcl_action/test/rcl_action/test_action_server.cpp +++ b/rcl_action/test/rcl_action/test_action_server.cpp @@ -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 diff --git a/rcl_action/test/rcl_action/test_goal_handle.cpp b/rcl_action/test/rcl_action/test_goal_handle.cpp index d0d2655023..3b28bbd11b 100644 --- a/rcl_action/test/rcl_action/test_goal_handle.cpp +++ b/rcl_action/test/rcl_action/test_goal_handle.cpp @@ -161,7 +161,7 @@ using EventStateActiveCancelableTuple = std::tuple; using StateTransitionSequence = std::vector; const std::vector event_strs = { - "EXECUTE", "CANCEL", "SET_SUCCEEDED", "SET_ABORTED", "SET_CANCELED"}; + "EXECUTE", "CANCEL", "SUCCEED", "ABORT", "CANCEL"}; class TestGoalHandleStateTransitionSequence : public ::testing::TestWithParam @@ -243,38 +243,38 @@ 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_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_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_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_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_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_SUCCEED, GOAL_STATE_SUCCEEDED, false, false), }, }; @@ -300,13 +300,13 @@ const StateTransitionSequence invalid_state_transition_sequences[] = { 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_CANCEL, 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), }, }; diff --git a/rcl_action/test/rcl_action/test_goal_state_machine.cpp b/rcl_action/test/rcl_action/test_goal_state_machine.cpp index 32d710204f..0e6fa7e886 100644 --- a/rcl_action/test/rcl_action/test_goal_state_machine.cpp +++ b/rcl_action/test/rcl_action/test_goal_state_machine.cpp @@ -32,19 +32,19 @@ TEST(TestGoalStateMachine, test_valid_transitions) 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_CANCEL); 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); } @@ -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_CANCEL); EXPECT_EQ(GOAL_STATE_UNKNOWN, state); // Invalid from EXECUTING @@ -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_CANCEL); EXPECT_EQ(GOAL_STATE_UNKNOWN, state); // Invalid from CANCELING @@ -95,15 +95,15 @@ TEST(TestGoalStateMachine, test_invalid_transitions) 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_CANCEL); EXPECT_EQ(GOAL_STATE_UNKNOWN, state); // Invalid from ABORTED @@ -117,15 +117,15 @@ TEST(TestGoalStateMachine, test_invalid_transitions) 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_CANCEL); EXPECT_EQ(GOAL_STATE_UNKNOWN, state); // Invalid from CANCELED @@ -139,14 +139,14 @@ TEST(TestGoalStateMachine, test_invalid_transitions) 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_CANCEL); EXPECT_EQ(GOAL_STATE_UNKNOWN, state); }