Skip to content

Commit a708084

Browse files
committed
Add pending queue to collector, remove from waitable
Signed-off-by: Michael Carroll <[email protected]>
1 parent 653d1a3 commit a708084

File tree

4 files changed

+238
-111
lines changed

4 files changed

+238
-111
lines changed

rclcpp/include/rclcpp/executors/executor_entities_collector.hpp

Lines changed: 24 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,8 @@ class ExecutorEntitiesCollector
7070
RCLCPP_PUBLIC
7171
~ExecutorEntitiesCollector();
7272

73+
bool has_pending();
74+
7375
/// Add a node to the entity collector
7476
/**
7577
* \param[in] node_ptr a shared pointer that points to a node base interface
@@ -164,63 +166,66 @@ class ExecutorEntitiesCollector
164166

165167
using WeakNodesToGuardConditionsMap = std::map<
166168
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
167-
const rclcpp::GuardCondition *,
169+
rclcpp::GuardCondition::WeakPtr,
168170
std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>;
169171

170172
using WeakGroupsToGuardConditionsMap = std::map<
171173
rclcpp::CallbackGroup::WeakPtr,
172-
const rclcpp::GuardCondition *,
174+
rclcpp::GuardCondition::WeakPtr,
173175
std::owner_less<rclcpp::CallbackGroup::WeakPtr>>;
174176

175177
RCLCPP_PUBLIC
176178
NodeCollection::iterator
177-
remove_weak_node(NodeCollection::iterator weak_node) RCPPUTILS_TSA_REQUIRES(mutex_);
179+
remove_weak_node(NodeCollection::iterator weak_node);
178180

179181
RCLCPP_PUBLIC
180182
CallbackGroupCollection::iterator
181183
remove_weak_callback_group(
182184
CallbackGroupCollection::iterator weak_group_it,
183-
CallbackGroupCollection & collection) RCPPUTILS_TSA_REQUIRES(mutex_);
185+
CallbackGroupCollection & collection);
184186

185187
RCLCPP_PUBLIC
186188
void
187189
add_callback_group_to_collection(
188190
rclcpp::CallbackGroup::SharedPtr group_ptr,
189-
CallbackGroupCollection & collection) RCPPUTILS_TSA_REQUIRES(mutex_);
191+
CallbackGroupCollection & collection);
190192

191193
RCLCPP_PUBLIC
192194
void
193195
remove_callback_group_from_collection(
194196
rclcpp::CallbackGroup::SharedPtr group_ptr,
195-
CallbackGroupCollection & collection) RCPPUTILS_TSA_REQUIRES(mutex_);
197+
CallbackGroupCollection & collection);
196198

197199
RCLCPP_PUBLIC
198200
void
199-
add_automatically_associated_callback_groups(
200-
const NodeCollection & nodes_to_check)
201-
RCPPUTILS_TSA_REQUIRES(mutex_);
201+
process_queues();
202202

203203
RCLCPP_PUBLIC
204204
void
205-
prune_invalid_nodes_and_groups() RCPPUTILS_TSA_REQUIRES(mutex_);
205+
add_automatically_associated_callback_groups(
206+
const NodeCollection & nodes_to_check);
206207

207-
mutable std::mutex mutex_;
208+
RCLCPP_PUBLIC
209+
void
210+
prune_invalid_nodes_and_groups();
208211

209212
/// Callback groups that were added via `add_callback_group`
210-
CallbackGroupCollection
211-
manually_added_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
213+
CallbackGroupCollection manually_added_groups_;
212214

213215
/// Callback groups that were added by their association with added nodes
214-
CallbackGroupCollection
215-
automatically_added_groups_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
216+
CallbackGroupCollection automatically_added_groups_;
216217

217218
/// nodes that are associated with the executor
218-
NodeCollection
219-
weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
219+
NodeCollection weak_nodes_;
220220

221-
WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
221+
std::mutex pending_mutex_;
222+
NodeCollection pending_added_nodes_;
223+
NodeCollection pending_removed_nodes_;
224+
CallbackGroupCollection pending_manually_added_groups_;
225+
CallbackGroupCollection pending_manually_removed_groups_;
222226

223-
WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
227+
WeakNodesToGuardConditionsMap weak_nodes_to_guard_conditions_;
228+
WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_;
224229

225230
std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_;
226231
};

rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp

Lines changed: 13 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <list>
1919
#include <memory>
20+
#include <set>
2021

2122
#include "rclcpp/guard_condition.hpp"
2223
#include "rclcpp/waitable.hpp"
@@ -33,6 +34,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
3334
public:
3435
RCLCPP_SMART_PTR_DEFINITIONS(ExecutorNotifyWaitable)
3536

37+
3638
// Constructor
3739
/**
3840
* \param[in] on_execute_callback Callback to execute when one of the conditions
@@ -45,6 +47,13 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
4547
RCLCPP_PUBLIC
4648
~ExecutorNotifyWaitable() override = default;
4749

50+
RCLCPP_PUBLIC
51+
ExecutorNotifyWaitable(const ExecutorNotifyWaitable & other);
52+
53+
54+
RCLCPP_PUBLIC
55+
ExecutorNotifyWaitable& operator=(const ExecutorNotifyWaitable & other );
56+
4857
/// Add conditions to the wait set
4958
/**
5059
* \param[inout] wait_set structure that conditions will be added to
@@ -85,15 +94,15 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
8594
*/
8695
RCLCPP_PUBLIC
8796
void
88-
add_guard_condition(const rclcpp::GuardCondition * guard_condition);
97+
add_guard_condition(rclcpp::GuardCondition::WeakPtr guard_condition);
8998

9099
/// Remove a guard condition from being waited on.
91100
/**
92101
* \param[in] guard_condition The guard condition to remove.
93102
*/
94103
RCLCPP_PUBLIC
95104
void
96-
remove_guard_condition(const rclcpp::GuardCondition * guard_condition);
105+
remove_guard_condition(rclcpp::GuardCondition::WeakPtr guard_condition);
97106

98107
/// Get the number of ready guard_conditions
99108
/**
@@ -107,17 +116,11 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
107116
/// Callback to run when waitable executes
108117
std::function<void(void)> execute_callback_;
109118

110-
/// The collection of guard conditions to be waited on.
111119
std::mutex guard_condition_mutex_;
112120

113121
/// The collection of guard conditions to be waited on.
114-
std::list<const rclcpp::GuardCondition *> notify_guard_conditions_;
115-
116-
/// The collection of guard conditions to be waited on.
117-
std::list<const rclcpp::GuardCondition *> to_add_;
118-
119-
/// The collection of guard conditions to be waited on.
120-
std::list<const rclcpp::GuardCondition *> to_remove_;
122+
std::set<rclcpp::GuardCondition::WeakPtr,
123+
std::owner_less<rclcpp::GuardCondition::WeakPtr>> notify_guard_conditions_;
121124
};
122125

123126
} // namespace executors

0 commit comments

Comments
 (0)