Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactor server goal handle's try_canceling() function #603

Merged
merged 2 commits into from
Jan 8, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 6 additions & 17 deletions rclcpp_action/src/server_goal_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,30 +111,19 @@ bool
ServerGoalHandleBase::try_canceling() noexcept
{
std::lock_guard<std::mutex> lock(rcl_handle_mutex_);
// Check if the goal reached a terminal state already
const bool active = rcl_action_goal_handle_is_active(rcl_handle_.get());
if (!active) {
return false;
}

rcl_ret_t ret;

// Get the current state
rcl_action_goal_state_t state = GOAL_STATE_UNKNOWN;
ret = rcl_action_goal_handle_get_status(rcl_handle_.get(), &state);
if (RCL_RET_OK != ret) {
return false;
}

// If it's not already canceling then transition to that state
if (GOAL_STATE_CANCELING != state) {
// Check if the goal is cancelable
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);
if (RCL_RET_OK != ret) {
return false;
}
}

// Get the state again
rcl_action_goal_state_t state = GOAL_STATE_UNKNOWN;
// Get the current state
ret = rcl_action_goal_handle_get_status(rcl_handle_.get(), &state);
if (RCL_RET_OK != ret) {
return false;
Expand Down