Skip to content

Commit 920a511

Browse files
committed
feat: modify to test multiple PublishedTime publishers
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 4afc579 commit 920a511

File tree

1 file changed

+84
-19
lines changed

1 file changed

+84
-19
lines changed

common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp

+84-19
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,17 @@ class PublishedTimePublisherTest : public ::testing::Test
2525
protected:
2626
std::shared_ptr<rclcpp::Node> node_{nullptr};
2727
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_{nullptr};
28-
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> test_publisher_{nullptr};
28+
29+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_{nullptr};
30+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_{nullptr};
31+
32+
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
33+
first_test_subscriber_{nullptr};
2934
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
30-
test_subscriber_{nullptr};
31-
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr published_time_{nullptr};
35+
second_test_subscriber_{nullptr};
36+
37+
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_{nullptr};
38+
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_{nullptr};
3239

3340
void SetUp() override
3441
{
@@ -37,25 +44,39 @@ class PublishedTimePublisherTest : public ::testing::Test
3744
// Simplify node and topic names for brevity and uniqueness
3845
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
3946
const std::string base_name =
40-
"published_time_publisher_" + test_name; // Base name for node and topics
41-
const std::string suffix = "/debug/published_time";
47+
"published_time_publisher_" + test_name; // Base name for node and topics
48+
const std::string suffix = "/debug/published_time"; // Suffix for published time topics
4249

4350
// Create a node
4451
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");
4552

46-
// Create a publisher
47-
test_publisher_ = node_->create_publisher<std_msgs::msg::Header>(base_name, 1);
53+
// Create the first publisher
54+
first_test_publisher_ =
55+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);
56+
57+
// Create the second publisher
58+
second_test_publisher_ =
59+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);
4860

4961
// Create a PublishedTimePublisher
5062
published_time_publisher_ =
5163
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());
5264

53-
// Create a subscriber
54-
test_subscriber_ = node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
55-
base_name + suffix, 1,
65+
// Create the first subscriber
66+
first_test_subscriber_ = node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
67+
base_name + "_topic1" + suffix, 1,
5668
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
57-
this->published_time_ = std::move(msg);
69+
this->first_published_time_ = std::move(msg);
5870
});
71+
72+
// Create the second subscriber
73+
second_test_subscriber_ =
74+
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
75+
base_name + "_topic2" + suffix, 1,
76+
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
77+
this->second_published_time_ = std::move(msg);
78+
});
79+
5980
rclcpp::spin_some(node_);
6081
}
6182

@@ -70,15 +91,15 @@ TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
7091
std_msgs::msg::Header header;
7192
header.stamp = rclcpp::Time(1234);
7293

73-
// Use Published Time Publisher with a timestamp
74-
published_time_publisher_->publish(test_publisher_, header);
94+
// Use Published Time Publisher .publish() with a header
95+
published_time_publisher_->publish(first_test_publisher_, header);
7596
rclcpp::spin_some(node_);
7697

7798
// Check if the published_time_ is created
78-
ASSERT_TRUE(published_time_ != nullptr);
99+
ASSERT_TRUE(first_published_time_ != nullptr);
79100

80101
// Check if the published time is the same as the header
81-
EXPECT_EQ(published_time_->header.stamp, header.stamp);
102+
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
82103
}
83104

84105
TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
@@ -89,13 +110,57 @@ TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
89110
std_msgs::msg::Header header;
90111
header.stamp = rclcpp::Time(4321);
91112

92-
// Use Published Time Publisher with a timestamp
93-
published_time_publisher_->publish(test_publisher_, header.stamp);
113+
// Use Published Time Publisher .publish() with a timestamp
114+
published_time_publisher_->publish(first_test_publisher_, header.stamp);
115+
rclcpp::spin_some(node_);
116+
117+
// Check if the published_time_ is created
118+
ASSERT_TRUE(first_published_time_ != nullptr);
119+
120+
// Check if the published time is the same as the header
121+
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
122+
}
123+
124+
TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithHeader)
125+
{
126+
// Check if the PublishedTimePublisher is created
127+
ASSERT_TRUE(published_time_publisher_ != nullptr);
128+
129+
std_msgs::msg::Header header;
130+
header.stamp = rclcpp::Time(12345);
131+
132+
// Use Published Time Publisher .publish() with a header for multiple publishers
133+
published_time_publisher_->publish(first_test_publisher_, header);
134+
published_time_publisher_->publish(second_test_publisher_, header);
135+
rclcpp::spin_some(node_);
136+
137+
// Check if the published_time_ is created
138+
ASSERT_TRUE(first_published_time_ != nullptr);
139+
ASSERT_TRUE(second_published_time_ != nullptr);
140+
141+
// Check if the published time is the same as the header
142+
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
143+
EXPECT_EQ(second_published_time_->header.stamp, header.stamp);
144+
}
145+
146+
TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithTimestamp)
147+
{
148+
// Check if the PublishedTimePublisher is created
149+
ASSERT_TRUE(published_time_publisher_ != nullptr);
150+
151+
std_msgs::msg::Header header;
152+
header.stamp = rclcpp::Time(12345);
153+
154+
// Use Published Time Publisher .publish() with a timestamp for multiple publishers
155+
published_time_publisher_->publish(first_test_publisher_, header.stamp);
156+
published_time_publisher_->publish(second_test_publisher_, header.stamp);
94157
rclcpp::spin_some(node_);
95158

96159
// Check if the published_time_ is created
97-
ASSERT_TRUE(published_time_ != nullptr);
160+
ASSERT_TRUE(first_published_time_ != nullptr);
161+
ASSERT_TRUE(second_published_time_ != nullptr);
98162

99163
// Check if the published time is the same as the header
100-
EXPECT_EQ(published_time_->header.stamp, header.stamp);
164+
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
165+
EXPECT_EQ(second_published_time_->header.stamp, header.stamp);
101166
}

0 commit comments

Comments
 (0)