Skip to content

Commit c24c3b0

Browse files
authored
feat(published_time_publisher): add unit test (#6610)
* feat(published_time_publisher): add unit test Signed-off-by: Berkay Karaman <brkay54@gmail.com> * feat: add nullpointer test Signed-off-by: Berkay Karaman <brkay54@gmail.com> * feat: simplify node and topic names Signed-off-by: Berkay Karaman <brkay54@gmail.com> * feat: modify to test multiple PublishedTime publishers Signed-off-by: Berkay Karaman <brkay54@gmail.com> * feat: change function name publish() -> publish_if_subscribed() Signed-off-by: Berkay Karaman <brkay54@gmail.com> * feat: update Signed-off-by: Berkay Karaman <brkay54@gmail.com> --------- Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent e1d19d6 commit c24c3b0

File tree

1 file changed

+272
-0
lines changed

1 file changed

+272
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,272 @@
1+
// Copyright 2024 The Autoware Contributors
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <rclcpp/rclcpp.hpp>
16+
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
17+
18+
#include <autoware_internal_msgs/msg/published_time.hpp>
19+
#include <std_msgs/msg/header.hpp>
20+
21+
#include <gtest/gtest.h>
22+
23+
class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test
24+
{
25+
protected:
26+
std::shared_ptr<rclcpp::Node> node_{nullptr};
27+
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_ptr_{
28+
nullptr};
29+
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};
32+
33+
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
34+
first_test_subscriber_ptr_{nullptr};
35+
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
36+
second_test_subscriber_ptr_{nullptr};
37+
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_;
43+
44+
void SetUp() override
45+
{
46+
// Simplify node and topic names for brevity and uniqueness
47+
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
48+
const std::string base_name =
49+
"published_time_publisher_" + test_name; // Base name for node and topics
50+
const std::string suffix = "/debug/published_time"; // Suffix for published time topics
51+
52+
// Initialize ROS node
53+
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");
54+
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+
63+
// Create the first publisher
64+
first_test_publisher_ptr_ =
65+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);
66+
67+
// Create the second publisher
68+
second_test_publisher_ptr_ =
69+
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);
70+
71+
// Create a PublishedTimePublisher
72+
published_time_publisher_ptr_ =
73+
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());
74+
75+
// Create the first subscriber
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+
});
82+
83+
// Create the second subscriber
84+
second_test_subscriber_ptr_ =
85+
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
86+
base_name + "_topic2" + suffix, 1,
87+
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
88+
this->second_published_time_ptr_ = std::move(msg);
89+
});
90+
91+
rclcpp::spin_some(node_);
92+
}
93+
94+
void TearDown() override {}
95+
};
96+
97+
class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test
98+
{
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};
106+
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);
150+
151+
// Use Published Time Publisher .publish_if_subscribed() with a header
152+
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
153+
rclcpp::spin_some(node_);
154+
155+
// Check if the published_time_ is created
156+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
157+
158+
// Check if the published time is the same as the header
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);
161+
}
162+
163+
TEST_F(PublishedTimePublisherWithSubscriptionTest, PublishMsgWithTimestamp)
164+
{
165+
// Check if the PublishedTimePublisher is created
166+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
167+
168+
// Use Published Time Publisher .publish_if_subscribed() with a timestamp
169+
published_time_publisher_ptr_->publish_if_subscribed(
170+
first_test_publisher_ptr_, first_header_.stamp);
171+
rclcpp::spin_some(node_);
172+
173+
// Check if the published_time_ is created
174+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
175+
176+
// Check if the published time is the same as the header
177+
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
178+
EXPECT_EQ(first_published_time_ptr_->header.frame_id, std::string(""));
179+
}
180+
181+
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithHeader)
182+
{
183+
// Check if the PublishedTimePublisher is created
184+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
185+
186+
// Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
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_);
189+
rclcpp::spin_some(node_);
190+
191+
// Check if the published_time_ is created
192+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
193+
ASSERT_TRUE(second_published_time_ptr_ != nullptr);
194+
195+
// Check if the published time is the same as the header
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);
200+
}
201+
202+
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithTimestamp)
203+
{
204+
// Check if the PublishedTimePublisher is created
205+
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);
206+
207+
// Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
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);
212+
rclcpp::spin_some(node_);
213+
214+
// Check if the published_time_ is created
215+
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
216+
ASSERT_TRUE(second_published_time_ptr_ != nullptr);
217+
218+
// Check if the published time is the same as the header
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());
272+
}

0 commit comments

Comments
 (0)