Skip to content

Commit

Permalink
Create test to prevent behavior regression
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed Apr 11, 2023
1 parent 7a72499 commit 0100d73
Showing 1 changed file with 92 additions and 0 deletions.
92 changes: 92 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -593,3 +593,95 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) {

rclcpp::shutdown();
}

template<typename T>
class TestIntraprocessExecutors : public ::testing::Test
{
public:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}

static void TearDownTestCase()
{
rclcpp::shutdown();
}

void SetUp()
{
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());

callback_count = 0;

const std::string topic_name = std::string("topic_") + test_name.str();

rclcpp::PublisherOptions po;
po.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, rclcpp::QoS(1), po);

auto callback = [this](test_msgs::msg::Empty::ConstSharedPtr) {
this->callback_count.fetch_add(1);
};

rclcpp::SubscriptionOptions so;
so.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
subscription =
node->create_subscription<test_msgs::msg::Empty>(
topic_name, rclcpp::QoS(kNumMessages), std::move(callback), so);
}

void TearDown()
{
publisher.reset();
subscription.reset();
node.reset();
}

const size_t kNumMessages = 100;

rclcpp::Node::SharedPtr node;
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
std::atomic_int callback_count;
};

TYPED_TEST_SUITE(TestIntraprocessExecutors, ExecutorTypes, ExecutorTypeNames);

TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
// This tests that executors will continue to service intraprocess subscriptions in the case
// that publishers aren't continuing to publish.
// This was previously broken in that intraprocess guard conditions were only triggered on
// publish and the test was added to prevent future regressions.
const size_t kNumMessages = 100;

using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_node(this->node);

EXPECT_EQ(0, this->callback_count.load());
this->publisher->publish(test_msgs::msg::Empty());

const std::chrono::milliseconds sleep_per_loop(10);
while (1u != this->callback_count.load()) {
rclcpp::sleep_for(sleep_per_loop);
executor.spin_some();
}
EXPECT_EQ(1u, this->callback_count.load());

// reset counter
this->callback_count.store(0);

for (size_t ii = 0; ii < kNumMessages; ++ii) {
this->publisher->publish(test_msgs::msg::Empty());
}
auto timer = this->node->create_wall_timer(
std::chrono::milliseconds(250), [&executor]() {
executor.cancel();
});
executor.spin();
EXPECT_EQ(kNumMessages, this->callback_count.load());
}

0 comments on commit 0100d73

Please sign in to comment.