Skip to content

Commit 3b7266c

Browse files
committed
Change get_guard_condition to return shared_ptr
Signed-off-by: Michael Carroll <[email protected]>
1 parent a708084 commit 3b7266c

File tree

9 files changed

+36
-24
lines changed

9 files changed

+36
-24
lines changed

rclcpp/include/rclcpp/node_interfaces/node_base.hpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -122,9 +122,13 @@ class NodeBase : public NodeBaseInterface, public std::enable_shared_from_this<N
122122
get_associated_with_executor_atomic() override;
123123

124124
RCLCPP_PUBLIC
125-
rclcpp::GuardCondition &
125+
rclcpp::GuardCondition::SharedPtr
126126
get_notify_guard_condition() override;
127127

128+
RCLCPP_PUBLIC
129+
void
130+
trigger_notify_guard_condition() override;
131+
128132
RCLCPP_PUBLIC
129133
bool
130134
get_use_intra_process_default() const override;
@@ -153,7 +157,7 @@ class NodeBase : public NodeBaseInterface, public std::enable_shared_from_this<N
153157

154158
/// Guard condition for notifying the Executor of changes to this node.
155159
mutable std::recursive_mutex notify_guard_condition_mutex_;
156-
rclcpp::GuardCondition notify_guard_condition_;
160+
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_;
157161
bool notify_guard_condition_is_valid_;
158162
};
159163

rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,9 +152,14 @@ class NodeBaseInterface
152152
*/
153153
RCLCPP_PUBLIC
154154
virtual
155-
rclcpp::GuardCondition &
155+
rclcpp::GuardCondition::SharedPtr
156156
get_notify_guard_condition() = 0;
157157

158+
RCLCPP_PUBLIC
159+
virtual
160+
void
161+
trigger_notify_guard_condition() = 0;
162+
158163
/// Return the default preference for using intra process communication.
159164
RCLCPP_PUBLIC
160165
virtual

rclcpp/src/rclcpp/node_interfaces/node_base.cpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ NodeBase::NodeBase(
4545
node_handle_(nullptr),
4646
default_callback_group_(default_callback_group),
4747
associated_with_executor_(false),
48-
notify_guard_condition_(context),
48+
notify_guard_condition_(std::make_shared<rclcpp::GuardCondition>(context)),
4949
notify_guard_condition_is_valid_(false)
5050
{
5151
// Create the rcl node and store it in a shared_ptr with a custom destructor.
@@ -254,7 +254,7 @@ NodeBase::get_associated_with_executor_atomic()
254254
return associated_with_executor_;
255255
}
256256

257-
rclcpp::GuardCondition &
257+
rclcpp::GuardCondition::SharedPtr
258258
NodeBase::get_notify_guard_condition()
259259
{
260260
std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
@@ -264,6 +264,16 @@ NodeBase::get_notify_guard_condition()
264264
return notify_guard_condition_;
265265
}
266266

267+
void
268+
NodeBase::trigger_notify_guard_condition()
269+
{
270+
std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
271+
if (!notify_guard_condition_is_valid_) {
272+
throw std::runtime_error("failed to trigger notify guard condition because it is invalid");
273+
}
274+
notify_guard_condition_->trigger();
275+
}
276+
267277
bool
268278
NodeBase::get_use_intra_process_default() const
269279
{

rclcpp/src/rclcpp/node_interfaces/node_graph.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -533,9 +533,8 @@ NodeGraph::notify_graph_change()
533533
}
534534
}
535535
graph_cv_.notify_all();
536-
auto & node_gc = node_base_->get_notify_guard_condition();
537536
try {
538-
node_gc.trigger();
537+
node_base_->trigger_notify_guard_condition();
539538
} catch (const rclcpp::exceptions::RCLError & ex) {
540539
throw std::runtime_error(
541540
std::string("failed to notify wait set on graph change: ") + ex.what());

rclcpp/src/rclcpp/node_interfaces/node_services.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,8 @@ NodeServices::add_service(
4242
group->add_service(service_base_ptr);
4343

4444
// Notify the executor that a new service was created using the parent Node.
45-
auto & node_gc = node_base_->get_notify_guard_condition();
4645
try {
47-
node_gc.trigger();
46+
node_base_->trigger_notify_guard_condition();
4847
group->trigger_notify_guard_condition();
4948
} catch (const rclcpp::exceptions::RCLError & ex) {
5049
throw std::runtime_error(
@@ -69,9 +68,8 @@ NodeServices::add_client(
6968
group->add_client(client_base_ptr);
7069

7170
// Notify the executor that a new client was created using the parent Node.
72-
auto & node_gc = node_base_->get_notify_guard_condition();
7371
try {
74-
node_gc.trigger();
72+
node_base_->trigger_notify_guard_condition();
7573
group->trigger_notify_guard_condition();
7674
} catch (const rclcpp::exceptions::RCLError & ex) {
7775
throw std::runtime_error(

rclcpp/src/rclcpp/node_interfaces/node_timers.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,8 @@ NodeTimers::add_timer(
4242
}
4343
callback_group->add_timer(timer);
4444

45-
auto & node_gc = node_base_->get_notify_guard_condition();
4645
try {
47-
node_gc.trigger();
46+
node_base_->trigger_notify_guard_condition();
4847
callback_group->trigger_notify_guard_condition();
4948
} catch (const rclcpp::exceptions::RCLError & ex) {
5049
throw std::runtime_error(

rclcpp/src/rclcpp/node_interfaces/node_topics.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -70,9 +70,8 @@ NodeTopics::add_publisher(
7070
}
7171

7272
// Notify the executor that a new publisher was created using the parent Node.
73-
auto & node_gc = node_base_->get_notify_guard_condition();
7473
try {
75-
node_gc.trigger();
74+
node_base_->trigger_notify_guard_condition();
7675
callback_group->trigger_notify_guard_condition();
7776
} catch (const rclcpp::exceptions::RCLError & ex) {
7877
throw std::runtime_error(
@@ -119,9 +118,8 @@ NodeTopics::add_subscription(
119118
}
120119

121120
// Notify the executor that a new subscription was created using the parent Node.
122-
auto & node_gc = node_base_->get_notify_guard_condition();
123121
try {
124-
node_gc.trigger();
122+
node_base_->trigger_notify_guard_condition();
125123
callback_group->trigger_notify_guard_condition();
126124
} catch (const rclcpp::exceptions::RCLError & ex) {
127125
throw std::runtime_error(

rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,8 @@ NodeWaitables::add_waitable(
4242
group->add_waitable(waitable_ptr);
4343

4444
// Notify the executor that a new waitable was created using the parent Node.
45-
auto & node_gc = node_base_->get_notify_guard_condition();
4645
try {
47-
node_gc.trigger();
46+
node_base_->trigger_notify_guard_condition();
4847
group->trigger_notify_guard_condition();
4948
} catch (const rclcpp::exceptions::RCLError & ex) {
5049
throw std::runtime_error(

rclcpp/test/rclcpp/executors/test_executor_notify_waitable.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -61,10 +61,10 @@ TEST_F(TestExecutorNotifyWaitable, add_remove_guard_conditions) {
6161
std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>(on_execute_callback);
6262

6363
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
64-
auto & notify_guard_condition = node->get_node_base_interface()->get_notify_guard_condition();
64+
auto notify_guard_condition = node->get_node_base_interface()->get_notify_guard_condition();
6565

66-
EXPECT_NO_THROW(waitable->add_guard_condition(&notify_guard_condition));
67-
EXPECT_NO_THROW(waitable->remove_guard_condition(&notify_guard_condition));
66+
EXPECT_NO_THROW(waitable->add_guard_condition(notify_guard_condition));
67+
EXPECT_NO_THROW(waitable->remove_guard_condition(notify_guard_condition));
6868
}
6969

7070
TEST_F(TestExecutorNotifyWaitable, wait) {
@@ -75,8 +75,8 @@ TEST_F(TestExecutorNotifyWaitable, wait) {
7575
std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>(on_execute_callback);
7676

7777
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
78-
auto & notify_guard_condition = node->get_node_base_interface()->get_notify_guard_condition();
79-
EXPECT_NO_THROW(waitable->add_guard_condition(&notify_guard_condition));
78+
auto notify_guard_condition = node->get_node_base_interface()->get_notify_guard_condition();
79+
EXPECT_NO_THROW(waitable->add_guard_condition(notify_guard_condition));
8080

8181
auto default_cbg = node->get_node_base_interface()->get_default_callback_group();
8282
ASSERT_NE(nullptr, default_cbg->get_notify_guard_condition());

0 commit comments

Comments
 (0)