Skip to content

Commit 1b50e4c

Browse files
committed
Introduce method to clear expired entities from a collection
Signed-off-by: Michael Carroll <[email protected]>
1 parent b812790 commit 1b50e4c

File tree

2 files changed

+30
-0
lines changed

2 files changed

+30
-0
lines changed

rclcpp/include/rclcpp/executors/executor_entities_collection.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,12 @@ struct ExecutorEntitiesCollection
178178

179179
/// Clear the entities collection
180180
void clear();
181+
182+
/// Remove entities that have expired weak ownership
183+
/**
184+
* \return The total number of removed entities
185+
*/
186+
size_t remove_expired_entities();
181187
};
182188

183189
/// Build an entities collection from callback groups

rclcpp/src/rclcpp/executors/executor_entities_collection.cpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,30 @@ void ExecutorEntitiesCollection::clear()
3939
waitables.clear();
4040
}
4141

42+
size_t ExecutorEntitiesCollection::remove_expired_entities()
43+
{
44+
auto remove_entities = [](auto & collection) -> size_t {
45+
size_t removed = 0;
46+
for (auto it = collection.begin(); it != collection.end(); ) {
47+
if (it->second.entity.expired()) {
48+
++removed;
49+
it = collection.erase(it);
50+
} else {
51+
++it;
52+
}
53+
}
54+
return removed;
55+
};
56+
57+
return
58+
remove_entities(subscriptions) +
59+
remove_entities(timers) +
60+
remove_entities(guard_conditions) +
61+
remove_entities(clients) +
62+
remove_entities(services) +
63+
remove_entities(waitables);
64+
}
65+
4266
void
4367
build_entities_collection(
4468
const std::vector<rclcpp::CallbackGroup::WeakPtr> & callback_groups,

0 commit comments

Comments
 (0)