Skip to content

Commit

Permalink
Make executor own the notify waitable
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Mar 31, 2023
1 parent e173e5a commit 653d1a3
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class ExecutorEntitiesCollector
*/
RCLCPP_PUBLIC
explicit ExecutorEntitiesCollector(
std::function<void(void)> on_notify_waitable_callback = {});
std::shared_ptr<ExecutorNotifyWaitable> notify_waitable);

/// Destructor
RCLCPP_PUBLIC
Expand Down Expand Up @@ -144,9 +144,6 @@ class ExecutorEntitiesCollector
std::vector<rclcpp::CallbackGroup::WeakPtr>
get_automatically_added_callback_groups();

RCLCPP_PUBLIC
std::shared_ptr<ExecutorNotifyWaitable> get_notify_waitable();

/// Update the underlying collections
/**
* This will prune nodes and callback groups that are no longer valid as well
Expand Down Expand Up @@ -225,7 +222,7 @@ class ExecutorEntitiesCollector

WeakGroupsToGuardConditionsMap weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);

std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
std::shared_ptr<ExecutorNotifyWaitable> notify_waitable_;
};
} // namespace executors
} // namespace rclcpp
Expand Down
10 changes: 2 additions & 8 deletions rclcpp/src/rclcpp/executors/executor_entities_collector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ namespace executors
{

ExecutorEntitiesCollector::ExecutorEntitiesCollector(
std::function<void(void)> on_notify_waitable_callback)
: notify_waitable_(std::make_shared<ExecutorNotifyWaitable>(on_notify_waitable_callback))
std::shared_ptr<ExecutorNotifyWaitable> notify_waitable)
: notify_waitable_(notify_waitable)
{
}

Expand Down Expand Up @@ -152,12 +152,6 @@ ExecutorEntitiesCollector::get_automatically_added_callback_groups()
return groups;
}

std::shared_ptr<ExecutorNotifyWaitable>
ExecutorEntitiesCollector::get_notify_waitable()
{
return this->notify_waitable_;
}

void
ExecutorEntitiesCollector::update_collections()
{
Expand Down
25 changes: 17 additions & 8 deletions rclcpp/test/rclcpp/executors/test_entities_collector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <gtest/gtest.h>

#include "rclcpp/executors/executor_notify_waitable.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/executors/executor_entities_collector.hpp"

Expand All @@ -34,7 +35,8 @@ class TestExecutorEntitiesCollector : public ::testing::Test
};

TEST_F(TestExecutorEntitiesCollector, add_remove_node) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node1 = std::make_shared<rclcpp::Node>("node1", "ns");
auto node2 = std::make_shared<rclcpp::Node>("node2", "ns");
Expand Down Expand Up @@ -78,7 +80,8 @@ TEST_F(TestExecutorEntitiesCollector, add_remove_node) {
}

TEST_F(TestExecutorEntitiesCollector, add_callback_group) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
Expand All @@ -91,7 +94,8 @@ TEST_F(TestExecutorEntitiesCollector, add_callback_group) {
}

TEST_F(TestExecutorEntitiesCollector, add_node_default_callback_group) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
entities_collector.add_node(node->get_node_base_interface());
Expand All @@ -102,7 +106,8 @@ TEST_F(TestExecutorEntitiesCollector, add_node_default_callback_group) {
}

TEST_F(TestExecutorEntitiesCollector, add_callback_group_after_add_node) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
Expand All @@ -115,7 +120,8 @@ TEST_F(TestExecutorEntitiesCollector, add_callback_group_after_add_node) {
}

TEST_F(TestExecutorEntitiesCollector, add_callback_group_twice) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
Expand All @@ -133,7 +139,8 @@ TEST_F(TestExecutorEntitiesCollector, add_callback_group_twice) {
}

TEST_F(TestExecutorEntitiesCollector, remove_callback_group_after_node) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
Expand All @@ -154,7 +161,8 @@ TEST_F(TestExecutorEntitiesCollector, remove_callback_group_after_node) {
}

TEST_F(TestExecutorEntitiesCollector, remove_callback_group_twice) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node = std::make_shared<rclcpp::Node>("node1", "ns");
rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group(
Expand All @@ -173,7 +181,8 @@ TEST_F(TestExecutorEntitiesCollector, remove_callback_group_twice) {
}

TEST_F(TestExecutorEntitiesCollector, remove_node_opposite_order) {
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector();
auto notify_waitable = std::make_shared<rclcpp::executors::ExecutorNotifyWaitable>();
auto entities_collector = rclcpp::executors::ExecutorEntitiesCollector(notify_waitable);

auto node1 = std::make_shared<rclcpp::Node>("node1", "ns");
EXPECT_NO_THROW(entities_collector.add_node(node1->get_node_base_interface()));
Expand Down

0 comments on commit 653d1a3

Please sign in to comment.