Skip to content

Commit

Permalink
Move release action to every exit point in different spin functions
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Jun 13, 2024
1 parent 5cf00c9 commit 0b4ab7e
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 7 deletions.
8 changes: 3 additions & 5 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,7 @@ Executor::spin_until_future_complete_impl(
if (spinning.exchange(true)) {
throw std::runtime_error("spin_until_future_complete() called while already spinning");
}
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
while (rclcpp::ok(this->context_) && spinning.load()) {
// Do one item of work.
spin_once_impl(timeout_left);
Expand Down Expand Up @@ -364,7 +364,7 @@ Executor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
if (spinning.exchange(true)) {
throw std::runtime_error("spin_some() called while already spinning");
}
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););

// clear the wait result and wait for work without blocking to collect the work
// for the first time
Expand Down Expand Up @@ -431,7 +431,7 @@ Executor::spin_once(std::chrono::nanoseconds timeout)
if (spinning.exchange(true)) {
throw std::runtime_error("spin_once() called while already spinning");
}
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
spin_once_impl(timeout);
}

Expand Down Expand Up @@ -885,8 +885,6 @@ Executor::get_next_executable(AnyExecutable & any_executable, std::chrono::nanos
// Wait for subscriptions or timers to work on
wait_for_work(timeout);
if (!spinning.load()) {
// Clear wait result to release ownership of entity
wait_result_.reset();
return false;
}
// Try again
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ MultiThreadedExecutor::spin()
if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false););
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
std::vector<std::thread> threads;
size_t thread_id = 0;
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ SingleThreadedExecutor::spin()
if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); wait_result_.reset(););

// Clear any previous result and rebuild the waitset
this->wait_result_.reset();
Expand Down

0 comments on commit 0b4ab7e

Please sign in to comment.