Skip to content

Commit

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

Now using active verbs as described in the design doc:

http://design.ros2.org/articles/actions.html#goal-states

Connects to ros2/rcl#399.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored and christopherho-ApexAI committed Jun 3, 2019
1 parent 3156e17 commit 3912abd
Show file tree
Hide file tree
Showing 4 changed files with 30 additions and 30 deletions.
2 changes: 1 addition & 1 deletion rclcpp_action/include/rclcpp_action/server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,7 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
if (goal_handle) {
resp = handle_cancel_(goal_handle);
if (CancelResponse::ACCEPT == resp) {
goal_handle->_set_canceling();
goal_handle->_cancel_goal();
}
}
}
Expand Down
26 changes: 13 additions & 13 deletions rclcpp_action/include/rclcpp_action/server_goal_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,27 +80,27 @@ class ServerGoalHandleBase
/// \internal
RCLCPP_ACTION_PUBLIC
void
_set_aborted();
_abort();

/// \internal
RCLCPP_ACTION_PUBLIC
void
_set_succeeded();
_succeed();

/// \internal
RCLCPP_ACTION_PUBLIC
void
_set_canceling();
_cancel_goal();

/// \internal
RCLCPP_ACTION_PUBLIC
void
_set_canceled();
_canceled();

/// \internal
RCLCPP_ACTION_PUBLIC
void
_set_executing();
_execute();

/// Transition the goal to canceled state if it never reached a terminal state.
/// \internal
Expand Down Expand Up @@ -165,9 +165,9 @@ class ServerGoalHandle : public ServerGoalHandleBase
* \param[in] result_msg the final result to send to clients.
*/
void
set_aborted(typename ActionT::Result::SharedPtr result_msg)
abort(typename ActionT::Result::SharedPtr result_msg)
{
_set_aborted();
_abort();
auto response = std::make_shared<typename ActionT::Impl::GetResultService::Response>();
response->status = action_msgs::msg::GoalStatus::STATUS_ABORTED;
response->result = *result_msg;
Expand All @@ -185,9 +185,9 @@ class ServerGoalHandle : public ServerGoalHandleBase
* \param[in] result_msg the final result to send to clients.
*/
void
set_succeeded(typename ActionT::Result::SharedPtr result_msg)
succeed(typename ActionT::Result::SharedPtr result_msg)
{
_set_succeeded();
_succeed();
auto response = std::make_shared<typename ActionT::Impl::GetResultService::Response>();
response->status = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED;
response->result = *result_msg;
Expand All @@ -205,9 +205,9 @@ class ServerGoalHandle : public ServerGoalHandleBase
* \param[in] result_msg the final result to send to clients.
*/
void
set_canceled(typename ActionT::Result::SharedPtr result_msg)
canceled(typename ActionT::Result::SharedPtr result_msg)
{
_set_canceled();
_canceled();
auto response = std::make_shared<typename ActionT::Impl::GetResultService::Response>();
response->status = action_msgs::msg::GoalStatus::STATUS_CANCELED;
response->result = *result_msg;
Expand All @@ -221,9 +221,9 @@ class ServerGoalHandle : public ServerGoalHandleBase
* \throws rclcpp::exceptions::RCLError If the goal is in any state besides executing.
*/
void
set_executing()
execute()
{
_set_executing();
_execute();
on_executing_(uuid_);
}

Expand Down
22 changes: 11 additions & 11 deletions rclcpp_action/src/server_goal_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,47 +58,47 @@ ServerGoalHandleBase::is_executing() const
}

void
ServerGoalHandleBase::_set_aborted()
ServerGoalHandleBase::_abort()
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SET_ABORTED);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_ABORT);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

void
ServerGoalHandleBase::_set_succeeded()
ServerGoalHandleBase::_succeed()
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SET_SUCCEEDED);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SUCCEED);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

void
ServerGoalHandleBase::_set_canceling()
ServerGoalHandleBase::_cancel_goal()
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCEL);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCEL_GOAL);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

void
ServerGoalHandleBase::_set_canceled()
ServerGoalHandleBase::_canceled()
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SET_CANCELED);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCELED);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
}

void
ServerGoalHandleBase::_set_executing()
ServerGoalHandleBase::_execute()
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
rcl_ret_t ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_EXECUTE);
Expand All @@ -116,7 +116,7 @@ ServerGoalHandleBase::try_canceling() noexcept
const bool is_cancelable = rcl_action_goal_handle_is_cancelable(rcl_handle_.get());
if (is_cancelable) {
// Transition to CANCELING
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCEL);
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCEL_GOAL);
if (RCL_RET_OK != ret) {
return false;
}
Expand All @@ -131,7 +131,7 @@ ServerGoalHandleBase::try_canceling() noexcept

// If it's canceling, cancel it
if (GOAL_STATE_CANCELING == state) {
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_SET_CANCELED);
ret = rcl_action_update_goal_state(rcl_handle_.get(), GOAL_EVENT_CANCELED);
return RCL_RET_OK == ret;
}

Expand Down
10 changes: 5 additions & 5 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -364,7 +364,7 @@ TEST_F(TestServer, publish_status_canceled)
send_goal_request(node, uuid);
send_cancel_request(node, uuid);

received_handle->set_canceled(std::make_shared<Fibonacci::Result>());
received_handle->canceled(std::make_shared<Fibonacci::Result>());

// 10 seconds
const size_t max_tries = 10 * 1000 / 100;
Expand Down Expand Up @@ -419,7 +419,7 @@ TEST_F(TestServer, publish_status_succeeded)
});

send_goal_request(node, uuid);
received_handle->set_succeeded(std::make_shared<Fibonacci::Result>());
received_handle->succeed(std::make_shared<Fibonacci::Result>());

// 10 seconds
const size_t max_tries = 10 * 1000 / 100;
Expand Down Expand Up @@ -474,7 +474,7 @@ TEST_F(TestServer, publish_status_aborted)
});

send_goal_request(node, uuid);
received_handle->set_aborted(std::make_shared<Fibonacci::Result>());
received_handle->abort(std::make_shared<Fibonacci::Result>());

// 10 seconds
const size_t max_tries = 10 * 1000 / 100;
Expand Down Expand Up @@ -592,7 +592,7 @@ TEST_F(TestServer, get_result)
// Send a result
auto result = std::make_shared<Fibonacci::Result>();
result->sequence = {5, 8, 13, 21};
received_handle->set_succeeded(result);
received_handle->succeed(result);

// Wait for the result request to be received
ASSERT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS,
Expand Down Expand Up @@ -637,6 +637,6 @@ TEST_F(TestServer, deferred_execution)

EXPECT_TRUE(received_handle->is_active());
EXPECT_FALSE(received_handle->is_executing());
received_handle->set_executing();
received_handle->execute();
EXPECT_TRUE(received_handle->is_executing());
}

0 comments on commit 3912abd

Please sign in to comment.