Skip to content

Commit

Permalink
Change get_guard_condition to return shared_ptr
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll committed Apr 3, 2023
1 parent a708084 commit 3b7266c
Show file tree
Hide file tree
Showing 9 changed files with 36 additions and 24 deletions.
8 changes: 6 additions & 2 deletions rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,9 +122,13 @@ class NodeBase : public NodeBaseInterface, public std::enable_shared_from_this<N
get_associated_with_executor_atomic() override;

RCLCPP_PUBLIC
rclcpp::GuardCondition &
rclcpp::GuardCondition::SharedPtr
get_notify_guard_condition() override;

RCLCPP_PUBLIC
void
trigger_notify_guard_condition() override;

RCLCPP_PUBLIC
bool
get_use_intra_process_default() const override;
Expand Down Expand Up @@ -153,7 +157,7 @@ class NodeBase : public NodeBaseInterface, public std::enable_shared_from_this<N

/// Guard condition for notifying the Executor of changes to this node.
mutable std::recursive_mutex notify_guard_condition_mutex_;
rclcpp::GuardCondition notify_guard_condition_;
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_;
bool notify_guard_condition_is_valid_;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,9 +152,14 @@ class NodeBaseInterface
*/
RCLCPP_PUBLIC
virtual
rclcpp::GuardCondition &
rclcpp::GuardCondition::SharedPtr
get_notify_guard_condition() = 0;

RCLCPP_PUBLIC
virtual
void
trigger_notify_guard_condition() = 0;

/// Return the default preference for using intra process communication.
RCLCPP_PUBLIC
virtual
Expand Down
14 changes: 12 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ NodeBase::NodeBase(
node_handle_(nullptr),
default_callback_group_(default_callback_group),
associated_with_executor_(false),
notify_guard_condition_(context),
notify_guard_condition_(std::make_shared<rclcpp::GuardCondition>(context)),
notify_guard_condition_is_valid_(false)
{
// Create the rcl node and store it in a shared_ptr with a custom destructor.
Expand Down Expand Up @@ -254,7 +254,7 @@ NodeBase::get_associated_with_executor_atomic()
return associated_with_executor_;
}

rclcpp::GuardCondition &
rclcpp::GuardCondition::SharedPtr
NodeBase::get_notify_guard_condition()
{
std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
Expand All @@ -264,6 +264,16 @@ NodeBase::get_notify_guard_condition()
return notify_guard_condition_;
}

void
NodeBase::trigger_notify_guard_condition()
{
std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
if (!notify_guard_condition_is_valid_) {
throw std::runtime_error("failed to trigger notify guard condition because it is invalid");
}
notify_guard_condition_->trigger();
}

bool
NodeBase::get_use_intra_process_default() const
{
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -533,9 +533,8 @@ NodeGraph::notify_graph_change()
}
}
graph_cv_.notify_all();
auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
std::string("failed to notify wait set on graph change: ") + ex.what());
Expand Down
6 changes: 2 additions & 4 deletions rclcpp/src/rclcpp/node_interfaces/node_services.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,8 @@ NodeServices::add_service(
group->add_service(service_base_ptr);

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

// Notify the executor that a new client was created using the parent Node.
auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
group->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,8 @@ NodeTimers::add_timer(
}
callback_group->add_timer(timer);

auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
callback_group->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
Expand Down
6 changes: 2 additions & 4 deletions rclcpp/src/rclcpp/node_interfaces/node_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,9 +70,8 @@ NodeTopics::add_publisher(
}

// Notify the executor that a new publisher was created using the parent Node.
auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
callback_group->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
Expand Down Expand Up @@ -119,9 +118,8 @@ NodeTopics::add_subscription(
}

// Notify the executor that a new subscription was created using the parent Node.
auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
callback_group->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
Expand Down
3 changes: 1 addition & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,8 @@ NodeWaitables::add_waitable(
group->add_waitable(waitable_ptr);

// Notify the executor that a new waitable was created using the parent Node.
auto & node_gc = node_base_->get_notify_guard_condition();
try {
node_gc.trigger();
node_base_->trigger_notify_guard_condition();
group->trigger_notify_guard_condition();
} catch (const rclcpp::exceptions::RCLError & ex) {
throw std::runtime_error(
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/test/rclcpp/executors/test_executor_notify_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,10 @@ TEST_F(TestExecutorNotifyWaitable, add_remove_guard_conditions) {
std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>(on_execute_callback);

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

EXPECT_NO_THROW(waitable->add_guard_condition(&notify_guard_condition));
EXPECT_NO_THROW(waitable->remove_guard_condition(&notify_guard_condition));
EXPECT_NO_THROW(waitable->add_guard_condition(notify_guard_condition));
EXPECT_NO_THROW(waitable->remove_guard_condition(notify_guard_condition));
}

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

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

auto default_cbg = node->get_node_base_interface()->get_default_callback_group();
ASSERT_NE(nullptr, default_cbg->get_notify_guard_condition());
Expand Down

0 comments on commit 3b7266c

Please sign in to comment.