Skip to content

Commit 6267741

Browse files
committed
Lint and docs
Signed-off-by: Michael Carroll <[email protected]>
1 parent 9dd48ce commit 6267741

File tree

3 files changed

+57
-5
lines changed

3 files changed

+57
-5
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -639,7 +639,7 @@ class Executor
639639
/// Guard condition for signaling the rmw layer to wake up for special events.
640640
std::shared_ptr<rclcpp::GuardCondition> interrupt_guard_condition_;
641641

642-
/// Guard condition for signaling the rmw layer to wake up for system shutdown.
642+
/// Guard condition for signaling the rmw layer to wake up for system shutdown.
643643
std::shared_ptr<rclcpp::GuardCondition> shutdown_guard_condition_;
644644

645645
/// Wait set for managing entities that the rmw layer waits on.

rclcpp/include/rclcpp/executors/executor_entities_collector.hpp

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -174,37 +174,76 @@ class ExecutorEntitiesCollector
174174
rclcpp::GuardCondition::WeakPtr,
175175
std::owner_less<rclcpp::CallbackGroup::WeakPtr>>;
176176

177+
/// Implementation of removing a node from the collector.
178+
/**
179+
* This will disassociate the node from the collector and remove any
180+
* automatically-added callback groups
181+
*
182+
* This takes and returns an iterator so it may be used as:
183+
*
184+
* it = remove_weak_node(it);
185+
*
186+
* \param[in] weak_node iterator to the weak node to be removed
187+
* \return Valid updated iterator in the same collection
188+
*/
177189
RCLCPP_PUBLIC
178190
NodeCollection::iterator
179191
remove_weak_node(NodeCollection::iterator weak_node);
180192

193+
/// Implementation of removing a callback gruop from the collector.
194+
/**
195+
* This will disassociate the callback group from the collector
196+
*
197+
* This takes and returns an iterator so it may be used as:
198+
*
199+
* it = remove_weak_callback_group(it);
200+
*
201+
* \param[in] weak_group_it iterator to the weak group to be removed
202+
* \param[in] collection the collection to remove the group from
203+
* (manually or automatically added)
204+
* \return Valid updated iterator in the same collection
205+
*/
181206
RCLCPP_PUBLIC
182207
CallbackGroupCollection::iterator
183208
remove_weak_callback_group(
184209
CallbackGroupCollection::iterator weak_group_it,
185210
CallbackGroupCollection & collection);
186211

212+
/// Implementation of adding a callback group
213+
/**
214+
* \param[in] group_ptr the group to add
215+
* \param[in] collection the collection to add the group to
216+
*/
187217
RCLCPP_PUBLIC
188218
void
189219
add_callback_group_to_collection(
190220
rclcpp::CallbackGroup::SharedPtr group_ptr,
191221
CallbackGroupCollection & collection);
192222

223+
/// Implementation of removing a callback group
224+
/**
225+
* \param[in] group_ptr the group to remove
226+
* \param[in] collection the collection to remove the group from
227+
*/
193228
RCLCPP_PUBLIC
194229
void
195230
remove_callback_group_from_collection(
196231
rclcpp::CallbackGroup::SharedPtr group_ptr,
197232
CallbackGroupCollection & collection);
198233

234+
/// Iterate over queued added/remove nodes and callback_groups
199235
RCLCPP_PUBLIC
200236
void
201237
process_queues();
202238

239+
/// Check a collection of nodes and add any new callback_groups that
240+
/// are set to be automatically associated via the node.
203241
RCLCPP_PUBLIC
204242
void
205243
add_automatically_associated_callback_groups(
206244
const NodeCollection & nodes_to_check);
207245

246+
/// Check all nodes and group for expired weak pointers and remove them.
208247
RCLCPP_PUBLIC
209248
void
210249
prune_invalid_nodes_and_groups();
@@ -218,15 +257,28 @@ class ExecutorEntitiesCollector
218257
/// nodes that are associated with the executor
219258
NodeCollection weak_nodes_;
220259

260+
/// mutex to protect pending queues
221261
std::mutex pending_mutex_;
262+
263+
/// nodes that have been added since the last update.
222264
NodeCollection pending_added_nodes_;
265+
266+
/// nodes that have been removed since the last update.
223267
NodeCollection pending_removed_nodes_;
268+
269+
/// callback groups that have been added since the last update.
224270
CallbackGroupCollection pending_manually_added_groups_;
271+
272+
/// callback groups that have been removed since the last update.
225273
CallbackGroupCollection pending_manually_removed_groups_;
226274

275+
/// Track guard conditions associated with added nodes
227276
WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_;
277+
278+
/// Track guard conditions associated with added callback groups
228279
WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_;
229280

281+
/// Waitable to add guard conditions to
230282
std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_;
231283
};
232284
} // namespace executors

rclcpp/src/rclcpp/executors/executor_entities_collector.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -295,7 +295,7 @@ ExecutorEntitiesCollector::process_queues()
295295
{
296296
std::lock_guard pending_lock(pending_mutex_);
297297

298-
for (auto weak_node_ptr: pending_added_nodes_) {
298+
for (auto weak_node_ptr : pending_added_nodes_) {
299299
auto node_ptr = weak_node_ptr.lock();
300300
if (!node_ptr) {
301301
continue;
@@ -310,7 +310,7 @@ ExecutorEntitiesCollector::process_queues()
310310
}
311311
pending_added_nodes_.clear();
312312

313-
for (auto weak_node_ptr: pending_removed_nodes_) {
313+
for (auto weak_node_ptr : pending_removed_nodes_) {
314314
auto node_it = weak_nodes_.find(weak_node_ptr);
315315
if (node_it != weak_nodes_.end()) {
316316
remove_weak_node(node_it);
@@ -334,15 +334,15 @@ ExecutorEntitiesCollector::process_queues()
334334
}
335335
pending_removed_nodes_.clear();
336336

337-
for (auto weak_group_ptr: pending_manually_added_groups_) {
337+
for (auto weak_group_ptr : pending_manually_added_groups_) {
338338
auto group_ptr = weak_group_ptr.lock();
339339
if (group_ptr) {
340340
this->add_callback_group_to_collection(group_ptr, manually_added_groups_);
341341
}
342342
}
343343
pending_manually_added_groups_.clear();
344344

345-
for (auto weak_group_ptr: pending_manually_removed_groups_) {
345+
for (auto weak_group_ptr : pending_manually_removed_groups_) {
346346
auto group_ptr = weak_group_ptr.lock();
347347
if (group_ptr) {
348348
this->remove_callback_group_from_collection(group_ptr, manually_added_groups_);

0 commit comments

Comments
 (0)