File tree Expand file tree Collapse file tree 1 file changed +17
-0
lines changed Expand file tree Collapse file tree 1 file changed +17
-0
lines changed Original file line number Diff line number Diff line change @@ -729,18 +729,35 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
729729 // Clear any previous wait result
730730 this ->wait_result_ .reset ();
731731
732+ // we need to make sure that callback groups don't get out of scope
733+ // during the wait. As in jazzy, they are not covered by the DynamicStorage,
734+ // we explicitly hold them here as a bugfix
735+ std::vector<rclcpp::CallbackGroup::SharedPtr> cbgs;
736+
732737 {
733738 std::lock_guard<std::mutex> guard (mutex_);
739+
734740 if (this ->entities_need_rebuild_ .exchange (false ) || current_collection_.empty ()) {
735741 this ->collect_entities ();
736742 }
743+
744+ auto callback_groups = this ->collector_ .get_all_callback_groups ();
745+ cbgs.resize (callback_groups.size ());
746+ for (const auto & w_ptr : callback_groups) {
747+ auto shr_ptr = w_ptr.lock ();
748+ if (shr_ptr) {
749+ cbgs.push_back (std::move (shr_ptr));
750+ }
751+ }
737752 }
738753 this ->wait_result_ .emplace (wait_set_.wait (timeout));
739754 if (!this ->wait_result_ || this ->wait_result_ ->kind () == WaitResultKind::Empty) {
740755 RCUTILS_LOG_WARN_NAMED (
741756 " rclcpp" ,
742757 " empty wait set received in wait(). This should never happen." );
743758 } else {
759+ // drop references to the callback groups, before trying to execute anything
760+ cbgs.clear ();
744761 if (this ->wait_result_ ->kind () == WaitResultKind::Ready && current_notify_waitable_) {
745762 auto & rcl_wait_set = this ->wait_result_ ->get_wait_set ().get_rcl_wait_set ();
746763 if (current_notify_waitable_->is_ready (rcl_wait_set)) {
You can’t perform that action at this time.
0 commit comments