Skip to content

Commit e173e5a

Browse files
committed
Lint and docs
Signed-off-by: Michael Carroll <[email protected]>
1 parent 9695eaa commit e173e5a

File tree

5 files changed

+108
-39
lines changed

5 files changed

+108
-39
lines changed

rclcpp/include/rclcpp/executors/executor_entities_collection.hpp

Lines changed: 75 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -32,16 +32,37 @@ namespace rclcpp
3232
namespace executors
3333
{
3434

35+
/// Structure to represent a single entity's entry in a collection
3536
template<typename EntityValueType>
3637
struct CollectionEntry
3738
{
39+
/// Weak pointer to entity type
3840
using EntityWeakPtr = typename EntityValueType::WeakPtr;
41+
/// Shared pointer to entity type
3942
using EntitySharedPtr = typename EntityValueType::SharedPtr;
4043

44+
/// The entity
4145
EntityWeakPtr entity;
46+
47+
/// If relevant, the entity's corresponding callback_group
4248
rclcpp::CallbackGroup::WeakPtr callback_group;
4349
};
4450

51+
/// Update a collection based on another collection
52+
/*
53+
* Iterates update_from and update_to to see which entities have been added/removed between
54+
* the two collections.
55+
*
56+
* For each new entry (in update_from, but not in update_to),
57+
* add the entity and fire the on_added callback
58+
* For each removed entry (in update_to, but not in update_from),
59+
* remove the entity and fire the on_removed callback.
60+
*
61+
* \param[in] update_from The collection representing the next iteration's state
62+
* \param[inout] update_to The collection representing the current iteration's state
63+
* \param[in] on_added Callback fired when a new entity is detected
64+
* \param[in] on_removed Callback fired when an entity is removed
65+
*/
4566
template<typename CollectionType>
4667
void update_entities(
4768
const CollectionType & update_from,
@@ -71,15 +92,31 @@ void update_entities(
7192
}
7293
}
7394
}
95+
96+
/// A collection of entities, indexed by their corresponding handles
7497
template<typename EntityKeyType, typename EntityValueType>
7598
class EntityCollection
7699
: public std::unordered_map<const EntityKeyType *, CollectionEntry<EntityValueType>>
77100
{
78101
public:
102+
/// Key type of the map
79103
using Key = const EntityKeyType *;
104+
105+
/// Weak pointer to entity type
80106
using EntityWeakPtr = typename EntityValueType::WeakPtr;
107+
108+
/// Shared pointer to entity type
81109
using EntitySharedPtr = typename EntityValueType::SharedPtr;
82110

111+
/// Update this collection based on the contents of another collection
112+
/**
113+
* Update the internal state of this collection, firing callbacks when entities have been
114+
* added or removed.
115+
*
116+
* \param[in] other Collection to compare to
117+
* \param[in] on_added Callback for when entities have been added
118+
* \param[in] on_removed Callback for when entities have been removed
119+
*/
83120
void update(
84121
const EntityCollection<EntityKeyType, EntityValueType> & other,
85122
std::function<void(EntitySharedPtr)> on_added,
@@ -96,40 +133,72 @@ class EntityCollection
96133
*/
97134
struct ExecutorEntitiesCollection
98135
{
99-
/// Entity entries for timers
136+
/// Collection type for timer entities
100137
using TimerCollection = EntityCollection<rcl_timer_t, rclcpp::TimerBase>;
101138

102-
/// Entity entries for subscriptions
139+
/// Collection type for subscription entities
103140
using SubscriptionCollection = EntityCollection<rcl_subscription_t, rclcpp::SubscriptionBase>;
104141

105-
/// Entity entries for clients
142+
/// Collection type for client entities
106143
using ClientCollection = EntityCollection<rcl_client_t, rclcpp::ClientBase>;
107144

108-
/// Entity entries for services
145+
/// Collection type for service entities
109146
using ServiceCollection = EntityCollection<rcl_service_t, rclcpp::ServiceBase>;
110147

111-
/// Entity entries for waitables
148+
/// Collection type for waitable entities
112149
using WaitableCollection = EntityCollection<rclcpp::Waitable, rclcpp::Waitable>;
113150

114-
/// Entity entries for guard conditions
151+
/// Collection type for guard condition entities
115152
using GuardConditionCollection = EntityCollection<rcl_guard_condition_t, rclcpp::GuardCondition>;
116153

154+
/// Collection of timers currently in use by the executor.
117155
TimerCollection timers;
156+
157+
/// Collection of subscriptions currently in use by the executor.
118158
SubscriptionCollection subscriptions;
159+
160+
/// Collection of clients currently in use by the executor.
119161
ClientCollection clients;
162+
163+
/// Collection of services currently in use by the executor.
120164
ServiceCollection services;
165+
166+
/// Collection of guard conditions currently in use by the executor.
121167
GuardConditionCollection guard_conditions;
168+
169+
/// Collection of waitables currently in use by the executor.
122170
WaitableCollection waitables;
123171

172+
/// Check if the entities collection is empty
173+
/**
174+
* \return true if all member collections are empty, false otherwise
175+
*/
124176
bool empty() const;
177+
178+
/// Clear the entities collection
125179
void clear();
126180
};
127181

182+
/// Build an entities collection from callback groups
183+
/**
184+
* Iterates a list of callback groups and adds entities from each valid group
185+
*
186+
* \param[in] callback_groups List of callback groups to check for entities
187+
* \param[inout] colletion Entities collection to populate with found entities
188+
*/
128189
void
129190
build_entities_collection(
130191
const std::vector<rclcpp::CallbackGroup::WeakPtr> & callback_groups,
131192
ExecutorEntitiesCollection & collection);
132193

194+
/// Build a queue of executables ready to be executed
195+
/**
196+
* Iterates a list of entities and adds them to a queue if they are ready.
197+
*
198+
* \param[in] collection Collection of entities corresponding to the current wait set.
199+
* \param[in] wait_result Result of rclcpp::WaitSet::wait corresponding to the collection.
200+
* \return A queue of executables that have been marked ready by the waitset.
201+
*/
133202
std::deque<rclcpp::AnyExecutable>
134203
ready_executables(
135204
const ExecutorEntitiesCollection & collection,

rclcpp/include/rclcpp/executors/executor_entities_collector.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define RCLCPP__EXECUTORS__EXECUTOR_ENTITIES_COLLECTOR_HPP_
1717

1818
#include <list>
19+
#include <map>
1920
#include <memory>
2021
#include <set>
2122
#include <vector>

rclcpp/src/rclcpp/executors/executor_entities_collection.cpp

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,12 @@ namespace executors
2020
{
2121
bool ExecutorEntitiesCollection::empty() const
2222
{
23-
return (subscriptions.empty() &&
24-
timers.empty() &&
25-
guard_conditions.empty() &&
26-
clients.empty() &&
27-
services.empty() &&
28-
waitables.empty());
23+
return subscriptions.empty() &&
24+
timers.empty() &&
25+
guard_conditions.empty() &&
26+
clients.empty() &&
27+
services.empty() &&
28+
waitables.empty();
2929
}
3030

3131
void ExecutorEntitiesCollection::clear()
@@ -52,8 +52,7 @@ build_entities_collection(
5252
continue;
5353
}
5454

55-
if (group_ptr->can_be_taken_from().load())
56-
{
55+
if (group_ptr->can_be_taken_from().load()) {
5756
group_ptr->collect_all_ptrs(
5857
[&collection, weak_group_ptr](const rclcpp::SubscriptionBase::SharedPtr & subscription) {
5958
collection.subscriptions.insert(
@@ -102,7 +101,7 @@ void check_ready(
102101
size_t size_of_waited_entities,
103102
typename EntityCollectionType::Key * waited_entities,
104103
std::function<bool(rclcpp::AnyExecutable &,
105-
typename EntityCollectionType::EntitySharedPtr &)> fill_executable)
104+
typename EntityCollectionType::EntitySharedPtr &)> fill_executable)
106105
{
107106
for (size_t ii = 0; ii < size_of_waited_entities; ++ii) {
108107
if (waited_entities[ii]) {
@@ -122,7 +121,6 @@ void check_ready(
122121
exec.callback_group = callback_group;
123122
if (fill_executable(exec, entity)) {
124123
executables.push_back(exec);
125-
} else {
126124
}
127125
}
128126
}

rclcpp/src/rclcpp/executors/executor_entities_collector.cpp

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -33,16 +33,20 @@ ExecutorEntitiesCollector::~ExecutorEntitiesCollector()
3333
{
3434
std::lock_guard<std::mutex> guard{mutex_};
3535

36-
for (auto weak_node_it = weak_nodes_.begin(); weak_node_it != weak_nodes_.end();) {
36+
for (auto weak_node_it = weak_nodes_.begin(); weak_node_it != weak_nodes_.end(); ) {
3737
weak_node_it = remove_weak_node(weak_node_it);
3838
}
3939

40-
for (auto weak_group_it = automatically_added_groups_.begin(); weak_group_it != automatically_added_groups_.end(); ) {
41-
weak_group_it= remove_weak_callback_group(weak_group_it, automatically_added_groups_);
40+
for (auto weak_group_it = automatically_added_groups_.begin();
41+
weak_group_it != automatically_added_groups_.end(); )
42+
{
43+
weak_group_it = remove_weak_callback_group(weak_group_it, automatically_added_groups_);
4244
}
4345

44-
for (auto weak_group_it = manually_added_groups_.begin(); weak_group_it != manually_added_groups_.end(); ) {
45-
weak_group_it= remove_weak_callback_group(weak_group_it, manually_added_groups_);
46+
for (auto weak_group_it = manually_added_groups_.begin();
47+
weak_group_it != manually_added_groups_.end(); )
48+
{
49+
weak_group_it = remove_weak_callback_group(weak_group_it, manually_added_groups_);
4650
}
4751
}
4852

@@ -86,13 +90,12 @@ ExecutorEntitiesCollector::remove_node(
8690
}
8791

8892
for (auto group_it = automatically_added_groups_.begin();
89-
group_it != automatically_added_groups_.end();)
93+
group_it != automatically_added_groups_.end(); )
9094
{
9195
auto group_ptr = group_it->lock();
9296
if (node_ptr->callback_group_in_node(group_ptr)) {
9397
group_it = remove_weak_callback_group(group_it, automatically_added_groups_);
94-
}
95-
else {
98+
} else {
9699
++group_it;
97100
}
98101
}
@@ -168,8 +171,7 @@ ExecutorEntitiesCollector::remove_weak_node(NodeCollection::iterator weak_node)
168171
{
169172
// Disassociate the guard condition from the executor notify waitable
170173
auto guard_condition_it = weak_nodes_to_guard_conditions_.find(*weak_node);
171-
if (guard_condition_it != weak_nodes_to_guard_conditions_.end())
172-
{
174+
if (guard_condition_it != weak_nodes_to_guard_conditions_.end()) {
173175
this->notify_waitable_->remove_guard_condition(guard_condition_it->second);
174176
weak_nodes_to_guard_conditions_.erase(guard_condition_it);
175177
}
@@ -193,8 +195,7 @@ ExecutorEntitiesCollector::remove_weak_callback_group(
193195
{
194196
// Disassociate the guard condition from the executor notify waitable
195197
auto guard_condition_it = weak_groups_to_guard_conditions_.find(*weak_group_it);
196-
if (guard_condition_it != weak_groups_to_guard_conditions_.end())
197-
{
198+
if (guard_condition_it != weak_groups_to_guard_conditions_.end()) {
198199
this->notify_waitable_->remove_guard_condition(guard_condition_it->second);
199200
weak_groups_to_guard_conditions_.erase(guard_condition_it);
200201
}

rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -103,23 +103,23 @@ ExecutorNotifyWaitable::get_number_of_ready_guard_conditions()
103103
{
104104
std::lock_guard<std::mutex> lock(guard_condition_mutex_);
105105

106-
for (auto add_guard_condition: to_add_)
107-
{
108-
auto guard_it = std::find(notify_guard_conditions_.begin(),
109-
notify_guard_conditions_.end(),
110-
add_guard_condition);
106+
for (auto add_guard_condition : to_add_) {
107+
auto guard_it = std::find(
108+
notify_guard_conditions_.begin(),
109+
notify_guard_conditions_.end(),
110+
add_guard_condition);
111111
if (guard_it == notify_guard_conditions_.end()) {
112112
notify_guard_conditions_.push_back(add_guard_condition);
113113
}
114114
}
115115
to_add_.clear();
116116

117-
for (auto remove_guard_condition: to_remove_)
118-
{
119-
auto guard_it = std::find(notify_guard_conditions_.begin(),
120-
notify_guard_conditions_.end(),
121-
remove_guard_condition);
122-
if (guard_it != notify_guard_conditions_.end()){
117+
for (auto remove_guard_condition : to_remove_) {
118+
auto guard_it = std::find(
119+
notify_guard_conditions_.begin(),
120+
notify_guard_conditions_.end(),
121+
remove_guard_condition);
122+
if (guard_it != notify_guard_conditions_.end()) {
123123
notify_guard_conditions_.erase(guard_it);
124124
}
125125
}

0 commit comments

Comments
 (0)