Skip to content

Commit 429fc32

Browse files
committed
Move release action to every exit point in different spin functions
Signed-off-by: Barry Xu <[email protected]>
1 parent 118773c commit 429fc32

File tree

3 files changed

+5
-7
lines changed

3 files changed

+5
-7
lines changed

rclcpp/src/rclcpp/executor.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -275,7 +275,7 @@ Executor::spin_until_future_complete_impl(
275275
if (spinning.exchange(true)) {
276276
throw std::runtime_error("spin_until_future_complete() called while already spinning");
277277
}
278-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
278+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
279279
while (rclcpp::ok(this->context_) && spinning.load()) {
280280
// Do one item of work.
281281
spin_once_impl(timeout_left);
@@ -364,7 +364,7 @@ Executor::spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive)
364364
if (spinning.exchange(true)) {
365365
throw std::runtime_error("spin_some() called while already spinning");
366366
}
367-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
367+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
368368

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

@@ -885,8 +885,6 @@ Executor::get_next_executable(AnyExecutable & any_executable, std::chrono::nanos
885885
// Wait for subscriptions or timers to work on
886886
wait_for_work(timeout);
887887
if (!spinning.load()) {
888-
// Clear wait result to release ownership of entity
889-
wait_result_.reset();
890888
return false;
891889
}
892890
// Try again

rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ MultiThreadedExecutor::spin()
5555
if (spinning.exchange(true)) {
5656
throw std::runtime_error("spin() called while already spinning");
5757
}
58-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false););
58+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false);wait_result_.reset(););
5959
std::vector<std::thread> threads;
6060
size_t thread_id = 0;
6161
{

rclcpp/src/rclcpp/executors/single_threaded_executor.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ SingleThreadedExecutor::spin()
3030
if (spinning.exchange(true)) {
3131
throw std::runtime_error("spin() called while already spinning");
3232
}
33-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
33+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); wait_result_.reset(););
3434

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

0 commit comments

Comments
 (0)