Skip to content

Commit

Permalink
A possible solution
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 Nov 19, 2024
1 parent 88ebea9 commit fbe602f
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -735,7 +735,20 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
this->collect_entities();
}
}

// Lock callback group
std::vector<rclcpp::CallbackGroup::SharedPtr> callback_group_sharedptr_list;
auto callback_groups_weakptr_list = collector_.get_all_callback_groups();
for (auto & callback_group_weakptr : callback_groups_weakptr_list) {
auto callback_group_sharedptr = callback_group_weakptr.lock();
if (callback_group_sharedptr) {
callback_group_sharedptr_list.emplace_back(std::move(callback_group_sharedptr));
}
}
this->wait_result_.emplace(wait_set_.wait(timeout));
// Free the lock of callback group
callback_group_sharedptr_list.clear();

if (!this->wait_result_ || this->wait_result_->kind() == WaitResultKind::Empty) {
RCUTILS_LOG_WARN_NAMED(
"rclcpp",
Expand Down

0 comments on commit fbe602f

Please sign in to comment.