Skip to content

Commit 39f6de0

Browse files
Address review: remove mutable, use remove_if, fix style
- Remove mutable from entity vectors, make collect_all_ptrs non-const - Replace collect_and_compact helper with std::remove_if (erase-remove idiom) - Remove leaked test_time_source_deadlock CMake entry from another branch - Fix uncrustify formatting in test file Signed-off-by: Pavel Guzenfeld <pavelguzenfeld@gmail.com>
1 parent 436d34c commit 39f6de0

4 files changed

Lines changed: 68 additions & 44 deletions

File tree

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ class CallbackGroup
183183
const std::function<void(const rclcpp::ServiceBase::SharedPtr &)> & service_func,
184184
const std::function<void(const rclcpp::ClientBase::SharedPtr &)> & client_func,
185185
const std::function<void(const rclcpp::TimerBase::SharedPtr &)> & timer_func,
186-
const std::function<void(const rclcpp::Waitable::SharedPtr &)> & waitable_func) const;
186+
const std::function<void(const rclcpp::Waitable::SharedPtr &)> & waitable_func);
187187

188188
/// Return a reference to the 'associated with executor' atomic boolean.
189189
/**
@@ -258,11 +258,11 @@ class CallbackGroup
258258
// Mutex to protect the subsequent vectors of pointers.
259259
mutable std::mutex mutex_;
260260
std::atomic_bool associated_with_executor_;
261-
mutable std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs_;
262-
mutable std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs_;
263-
mutable std::vector<rclcpp::ServiceBase::WeakPtr> service_ptrs_;
264-
mutable std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs_;
265-
mutable std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
261+
std::vector<rclcpp::SubscriptionBase::WeakPtr> subscription_ptrs_;
262+
std::vector<rclcpp::TimerBase::WeakPtr> timer_ptrs_;
263+
std::vector<rclcpp::ServiceBase::WeakPtr> service_ptrs_;
264+
std::vector<rclcpp::ClientBase::WeakPtr> client_ptrs_;
265+
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
266266
std::atomic_bool can_be_taken_from_;
267267
const bool automatically_add_to_executor_with_node_;
268268
// defer the creation of the guard condition

rclcpp/src/rclcpp/callback_group.cpp

Lines changed: 60 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -68,44 +68,74 @@ CallbackGroup::size() const
6868
waitable_ptrs_.size();
6969
}
7070

71-
namespace
72-
{
73-
/// Iterate a vector of weak pointers, call func for each live entry,
74-
/// and compact expired entries out of the vector in a single pass.
75-
template<typename T, typename Func>
76-
void collect_and_compact(
77-
std::vector<typename T::WeakPtr> & ptrs,
78-
const Func & func)
79-
{
80-
size_t write_idx = 0;
81-
for (size_t read_idx = 0; read_idx < ptrs.size(); ++read_idx) {
82-
auto ref_ptr = ptrs[read_idx].lock();
83-
if (ref_ptr) {
84-
func(ref_ptr);
85-
if (write_idx != read_idx) {
86-
ptrs[write_idx] = std::move(ptrs[read_idx]);
87-
}
88-
++write_idx;
89-
}
90-
}
91-
ptrs.resize(write_idx);
92-
}
93-
} // namespace
94-
9571
void CallbackGroup::collect_all_ptrs(
9672
const std::function<void(const rclcpp::SubscriptionBase::SharedPtr &)> & sub_func,
9773
const std::function<void(const rclcpp::ServiceBase::SharedPtr &)> & service_func,
9874
const std::function<void(const rclcpp::ClientBase::SharedPtr &)> & client_func,
9975
const std::function<void(const rclcpp::TimerBase::SharedPtr &)> & timer_func,
100-
const std::function<void(const rclcpp::Waitable::SharedPtr &)> & waitable_func) const
76+
const std::function<void(const rclcpp::Waitable::SharedPtr &)> & waitable_func)
10177
{
10278
std::lock_guard<std::mutex> lock(mutex_);
10379

104-
collect_and_compact<rclcpp::SubscriptionBase>(subscription_ptrs_, sub_func);
105-
collect_and_compact<rclcpp::ServiceBase>(service_ptrs_, service_func);
106-
collect_and_compact<rclcpp::ClientBase>(client_ptrs_, client_func);
107-
collect_and_compact<rclcpp::TimerBase>(timer_ptrs_, timer_func);
108-
collect_and_compact<rclcpp::Waitable>(waitable_ptrs_, waitable_func);
80+
for (const auto & weak_ptr : subscription_ptrs_) {
81+
auto ref_ptr = weak_ptr.lock();
82+
if (ref_ptr) {
83+
sub_func(ref_ptr);
84+
}
85+
}
86+
subscription_ptrs_.erase(
87+
std::remove_if(
88+
subscription_ptrs_.begin(), subscription_ptrs_.end(),
89+
[](const auto & w) {return w.expired();}),
90+
subscription_ptrs_.end());
91+
92+
for (const auto & weak_ptr : service_ptrs_) {
93+
auto ref_ptr = weak_ptr.lock();
94+
if (ref_ptr) {
95+
service_func(ref_ptr);
96+
}
97+
}
98+
service_ptrs_.erase(
99+
std::remove_if(
100+
service_ptrs_.begin(), service_ptrs_.end(),
101+
[](const auto & w) {return w.expired();}),
102+
service_ptrs_.end());
103+
104+
for (const auto & weak_ptr : client_ptrs_) {
105+
auto ref_ptr = weak_ptr.lock();
106+
if (ref_ptr) {
107+
client_func(ref_ptr);
108+
}
109+
}
110+
client_ptrs_.erase(
111+
std::remove_if(
112+
client_ptrs_.begin(), client_ptrs_.end(),
113+
[](const auto & w) {return w.expired();}),
114+
client_ptrs_.end());
115+
116+
for (const auto & weak_ptr : timer_ptrs_) {
117+
auto ref_ptr = weak_ptr.lock();
118+
if (ref_ptr) {
119+
timer_func(ref_ptr);
120+
}
121+
}
122+
timer_ptrs_.erase(
123+
std::remove_if(
124+
timer_ptrs_.begin(), timer_ptrs_.end(),
125+
[](const auto & w) {return w.expired();}),
126+
timer_ptrs_.end());
127+
128+
for (const auto & weak_ptr : waitable_ptrs_) {
129+
auto ref_ptr = weak_ptr.lock();
130+
if (ref_ptr) {
131+
waitable_func(ref_ptr);
132+
}
133+
}
134+
waitable_ptrs_.erase(
135+
std::remove_if(
136+
waitable_ptrs_.begin(), waitable_ptrs_.end(),
137+
[](const auto & w) {return w.expired();}),
138+
waitable_ptrs_.end());
109139
}
110140

111141
std::atomic_bool &

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -442,12 +442,6 @@ ament_add_ros_isolated_gtest(test_time_source test_time_source.cpp
442442
if(TARGET test_time_source)
443443
target_link_libraries(test_time_source ${PROJECT_NAME} rcl::rcl)
444444
endif()
445-
ament_add_ros_isolated_gtest(test_time_source_deadlock test_time_source_deadlock.cpp
446-
TIMEOUT 60)
447-
if(TARGET test_time_source_deadlock)
448-
target_link_libraries(test_time_source_deadlock ${PROJECT_NAME})
449-
endif()
450-
451445
ament_add_ros_isolated_gtest(test_utilities test_utilities.cpp
452446
APPEND_LIBRARY_DIRS "${append_library_dirs}")
453447
ament_add_test_label(test_utilities mimick)

rclcpp/test/rclcpp/test_callback_group_entity_cleanup.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ TEST_F(TestCallbackGroupEntityCleanup, add_many_timers_is_not_quadratic)
182182
// With O(N²) the old code took ~429ms for 10K timers.
183183
// With O(N) we expect < 100ms for 5K timers even on slow CI.
184184
// Use a generous threshold to avoid flakiness.
185-
EXPECT_LT(ms, 5000) << "Adding " << N << " timers took " << ms
185+
EXPECT_LT(ms, 5000) << "Adding " << N << " timers took " << ms
186186
<< "ms — possible quadratic regression";
187187
}
188188

@@ -215,7 +215,7 @@ TEST_F(TestCallbackGroupEntityCleanup, interleaved_add_remove_cycles)
215215
[](const rclcpp::SubscriptionBase::SharedPtr &) {},
216216
[](const rclcpp::ServiceBase::SharedPtr &) {},
217217
[](const rclcpp::ClientBase::SharedPtr &) {},
218-
[&live](const rclcpp::TimerBase::SharedPtr &) { ++live; },
218+
[&live](const rclcpp::TimerBase::SharedPtr &) {++live;},
219219
[](const rclcpp::Waitable::SharedPtr &) {});
220220

221221
EXPECT_EQ(live, timers.size());

0 commit comments

Comments
 (0)