Skip to content

Commit 7c775fa

Browse files
committed
feat: update
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 287695c commit 7c775fa

File tree

1 file changed

+165
-59
lines changed

1 file changed

+165
-59
lines changed

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

+165-59
Original file line numberDiff line numberDiff line change
@@ -20,61 +20,72 @@
2020

2121
#include <gtest/gtest.h>
2222

23-
class PublishedTimePublisherTest : public ::testing::Test
23+
class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test
2424
{
2525
protected:
2626
std::shared_ptr<rclcpp::Node> node_{nullptr};
27-
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_{nullptr};
27+
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_ptr_{
28+
nullptr};
2829

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};
30+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_ptr_{nullptr};
31+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_ptr_{nullptr};
3132

3233
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
33-
first_test_subscriber_{nullptr};
34+
first_test_subscriber_ptr_{nullptr};
3435
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
35-
second_test_subscriber_{nullptr};
36+
second_test_subscriber_ptr_{nullptr};
3637

37-
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_{nullptr};
38-
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_{nullptr};
38+
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_ptr_{nullptr};
39+
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_ptr_{nullptr};
40+
41+
std_msgs::msg::Header first_header_;
42+
std_msgs::msg::Header second_header_;
3943

4044
void SetUp() override
4145
{
42-
ASSERT_TRUE(rclcpp::ok());
43-
4446
// Simplify node and topic names for brevity and uniqueness
4547
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
4648
const std::string base_name =
4749
"published_time_publisher_" + test_name; // Base name for node and topics
4850
const std::string suffix = "/debug/published_time"; // Suffix for published time topics
4951

50-
// Create a node
52+
// Initialize ROS node
5153
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");
5254

55+
ASSERT_TRUE(rclcpp::ok());
56+
57+
// init headers which will be used to publish
58+
first_header_.stamp = rclcpp::Time(0);
59+
first_header_.frame_id = "frame_id_1";
60+
second_header_.stamp = rclcpp::Time(1);
61+
second_header_.frame_id = "frame_id_2";
62+
5363
// Create the first publisher
54-
first_test_publisher_ =
64+
first_test_publisher_ptr_ =
5565
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);
5666

5767
// Create the second publisher
58-
second_test_publisher_ =
68+
second_test_publisher_ptr_ =
5969
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);
6070

6171
// Create a PublishedTimePublisher
62-
published_time_publisher_ =
72+
published_time_publisher_ptr_ =
6373
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());
6474

6575
// Create the first subscriber
66-
first_test_subscriber_ = node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
67-
base_name + "_topic1" + suffix, 1,
68-
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
69-
this->first_published_time_ = std::move(msg);
70-
});
76+
first_test_subscriber_ptr_ =
77+
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
78+
base_name + "_topic1" + suffix, 1,
79+
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
80+
this->first_published_time_ptr_ = std::move(msg);
81+
});
7182

7283
// Create the second subscriber
73-
second_test_subscriber_ =
84+
second_test_subscriber_ptr_ =
7485
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
7586
base_name + "_topic2" + suffix, 1,
7687
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
77-
this->second_published_time_ = std::move(msg);
88+
this->second_published_time_ptr_ = std::move(msg);
7889
});
7990

8091
rclcpp::spin_some(node_);
@@ -83,84 +94,179 @@ class PublishedTimePublisherTest : public ::testing::Test
8394
void TearDown() override {}
8495
};
8596

86-
TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
97+
class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test
8798
{
88-
// Check if the PublishedTimePublisher is created
89-
ASSERT_TRUE(published_time_publisher_ != nullptr);
99+
protected:
100+
std::shared_ptr<rclcpp::Node> node_{nullptr};
101+
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_ptr_{
102+
nullptr};
103+
104+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_ptr_{nullptr};
105+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_ptr_{nullptr};
90106

91-
std_msgs::msg::Header header;
92-
header.stamp = rclcpp::Time(1234);
107+
std_msgs::msg::Header first_header_;
108+
std_msgs::msg::Header second_header_;
109+
110+
void SetUp() override
111+
{
112+
// Simplify node and topic names for brevity and uniqueness
113+
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
114+
const std::string base_name =
115+
"published_time_publisher_" + test_name; // Base name for node and topics
116+
117+
// Initialize ROS node
118+
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");
119+
120+
ASSERT_TRUE(rclcpp::ok());
121+
122+
// init headers which will be used to publish
123+
first_header_.stamp = rclcpp::Time(0);
124+
first_header_.frame_id = "frame_id_1";
125+
second_header_.stamp = rclcpp::Time(1);
126+
second_header_.frame_id = "frame_id_2";
127+
128+
// Create the first publisher
129+
first_test_publisher_ptr_ =
130+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);
131+
132+
// Create the second publisher
133+
second_test_publisher_ptr_ =
134+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);
135+
136+
// Create a PublishedTimePublisher
137+
published_time_publisher_ptr_ =
138+
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());
139+
140+
rclcpp::spin_some(node_);
141+
}
142+
143+
void TearDown() override {}
144+
};
145+
146+
TEST_F(PublishedTimePublisherWithSubscriptionTest, PublishMsgWithHeader)
147+
{
148+
// Check if the PublishedTimePublisher is created
149+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
93150

94151
// Use Published Time Publisher .publish_if_subscribed() with a header
95-
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header);
152+
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
96153
rclcpp::spin_some(node_);
97154

98155
// Check if the published_time_ is created
99-
ASSERT_TRUE(first_published_time_ != nullptr);
156+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
100157

101158
// Check if the published time is the same as the header
102-
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
159+
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
160+
EXPECT_EQ(first_published_time_ptr_->header.frame_id, first_header_.frame_id);
103161
}
104162

105-
TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
163+
TEST_F(PublishedTimePublisherWithSubscriptionTest, PublishMsgWithTimestamp)
106164
{
107165
// Check if the PublishedTimePublisher is created
108-
ASSERT_TRUE(published_time_publisher_ != nullptr);
109-
110-
std_msgs::msg::Header header;
111-
header.stamp = rclcpp::Time(4321);
166+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
112167

113168
// Use Published Time Publisher .publish_if_subscribed() with a timestamp
114-
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header.stamp);
169+
published_time_publisher_ptr_->publish_if_subscribed(
170+
first_test_publisher_ptr_, first_header_.stamp);
115171
rclcpp::spin_some(node_);
116172

117173
// Check if the published_time_ is created
118-
ASSERT_TRUE(first_published_time_ != nullptr);
174+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
119175

120176
// Check if the published time is the same as the header
121-
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
177+
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
178+
EXPECT_EQ(first_published_time_ptr_->header.frame_id, std::string(""));
122179
}
123180

124-
TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithHeader)
181+
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithHeader)
125182
{
126183
// 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);
184+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
131185

132186
// Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
133-
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header);
134-
published_time_publisher_->publish_if_subscribed(second_test_publisher_, header);
187+
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
188+
published_time_publisher_ptr_->publish_if_subscribed(second_test_publisher_ptr_, second_header_);
135189
rclcpp::spin_some(node_);
136190

137191
// Check if the published_time_ is created
138-
ASSERT_TRUE(first_published_time_ != nullptr);
139-
ASSERT_TRUE(second_published_time_ != nullptr);
192+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
193+
ASSERT_TRUE(second_published_time_ptr_ != nullptr);
140194

141195
// 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);
196+
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
197+
EXPECT_EQ(second_published_time_ptr_->header.stamp, second_header_.stamp);
198+
EXPECT_EQ(first_published_time_ptr_->header.frame_id, first_header_.frame_id);
199+
EXPECT_EQ(second_published_time_ptr_->header.frame_id, second_header_.frame_id);
144200
}
145201

146-
TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithTimestamp)
202+
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithTimestamp)
147203
{
148204
// 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);
205+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
153206

154207
// Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
155-
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header.stamp);
156-
published_time_publisher_->publish_if_subscribed(second_test_publisher_, header.stamp);
208+
published_time_publisher_ptr_->publish_if_subscribed(
209+
first_test_publisher_ptr_, first_header_.stamp);
210+
published_time_publisher_ptr_->publish_if_subscribed(
211+
second_test_publisher_ptr_, second_header_.stamp);
157212
rclcpp::spin_some(node_);
158213

159214
// Check if the published_time_ is created
160-
ASSERT_TRUE(first_published_time_ != nullptr);
161-
ASSERT_TRUE(second_published_time_ != nullptr);
215+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
216+
ASSERT_TRUE(second_published_time_ptr_ != nullptr);
162217

163218
// Check if the published time is the same as the header
164-
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
165-
EXPECT_EQ(second_published_time_->header.stamp, header.stamp);
219+
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
220+
EXPECT_EQ(second_published_time_ptr_->header.stamp, second_header_.stamp);
221+
EXPECT_EQ(first_published_time_ptr_->header.frame_id, std::string(""));
222+
EXPECT_EQ(second_published_time_ptr_->header.frame_id, std::string(""));
223+
}
224+
225+
TEST_F(PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithHeader)
226+
{
227+
// Check if the PublishedTimePublisher is created
228+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
229+
230+
// Use Published Time Publisher .publish_if_subscribed() with a header
231+
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
232+
rclcpp::spin_some(node_);
233+
ASSERT_TRUE(rclcpp::ok());
234+
}
235+
236+
TEST_F(PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithTimestamp)
237+
{
238+
// Check if the PublishedTimePublisher is created
239+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
240+
241+
// Use Published Time Publisher .publish_if_subscribed() with a timestamp
242+
published_time_publisher_ptr_->publish_if_subscribed(
243+
first_test_publisher_ptr_, first_header_.stamp);
244+
rclcpp::spin_some(node_);
245+
ASSERT_TRUE(rclcpp::ok());
246+
}
247+
248+
TEST_F(PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithHeader)
249+
{
250+
// Check if the PublishedTimePublisher is created
251+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
252+
253+
// Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
254+
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
255+
published_time_publisher_ptr_->publish_if_subscribed(second_test_publisher_ptr_, second_header_);
256+
rclcpp::spin_some(node_);
257+
ASSERT_TRUE(rclcpp::ok());
258+
}
259+
260+
TEST_F(PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithTimestamp)
261+
{
262+
// Check if the PublishedTimePublisher is created
263+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
264+
265+
// Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
266+
published_time_publisher_ptr_->publish_if_subscribed(
267+
first_test_publisher_ptr_, first_header_.stamp);
268+
published_time_publisher_ptr_->publish_if_subscribed(
269+
second_test_publisher_ptr_, second_header_.stamp);
270+
rclcpp::spin_some(node_);
271+
ASSERT_TRUE(rclcpp::ok());
166272
}

0 commit comments

Comments
 (0)