@@ -34,19 +34,27 @@ class PublishedTimePublisherTest : public ::testing::Test
34
34
{
35
35
ASSERT_TRUE (rclcpp::ok ());
36
36
37
+ // Simplify node and topic names for brevity and uniqueness
38
+ const std::string test_name = ::testing::UnitTest::GetInstance ()->current_test_info ()->name ();
39
+ 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" ;
42
+
37
43
// Create a node
38
- node_ = std::make_shared<rclcpp::Node>(" PublishedTimePublisher_test_node" );
44
+ node_ = std::make_shared<rclcpp::Node>(base_name + " _node" );
45
+
39
46
// Create a publisher
40
- test_publisher_ =
41
- node_-> create_publisher <std_msgs::msg::Header>( " PublishedTimePublisher_test_topic " , 1 );
47
+ test_publisher_ = node_-> create_publisher <std_msgs::msg::Header>(base_name, 1 );
48
+
42
49
// Create a PublishedTimePublisher
43
50
published_time_publisher_ =
44
51
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get ());
52
+
45
53
// Create a subscriber
46
54
test_subscriber_ = node_->create_subscription <autoware_internal_msgs::msg::PublishedTime>(
47
- " PublishedTimePublisher_test_topic/debug/published_time " , 1 ,
48
- [this ](autoware_internal_msgs::msg::PublishedTime::SharedPtr msg) {
49
- this ->published_time_ = msg;
55
+ base_name + suffix , 1 ,
56
+ [this ](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
57
+ this ->published_time_ = std::move ( msg) ;
50
58
});
51
59
rclcpp::spin_some (node_);
52
60
}
@@ -56,12 +64,17 @@ class PublishedTimePublisherTest : public ::testing::Test
56
64
57
65
TEST_F (PublishedTimePublisherTest, PublishMsgWithHeader)
58
66
{
67
+ // Check if the PublishedTimePublisher is created
68
+ ASSERT_TRUE (published_time_publisher_ != nullptr );
69
+
59
70
std_msgs::msg::Header header;
60
71
header.stamp = rclcpp::Time (1234 );
61
72
62
73
// Use Published Time Publisher with a timestamp
63
74
published_time_publisher_->publish (test_publisher_, header);
64
75
rclcpp::spin_some (node_);
76
+
77
+ // Check if the published_time_ is created
65
78
ASSERT_TRUE (published_time_ != nullptr );
66
79
67
80
// Check if the published time is the same as the header
@@ -70,12 +83,17 @@ TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
70
83
71
84
TEST_F (PublishedTimePublisherTest, PublishMsgWithTimestamp)
72
85
{
86
+ // Check if the PublishedTimePublisher is created
87
+ ASSERT_TRUE (published_time_publisher_ != nullptr );
88
+
73
89
std_msgs::msg::Header header;
74
90
header.stamp = rclcpp::Time (4321 );
75
91
76
92
// Use Published Time Publisher with a timestamp
77
93
published_time_publisher_->publish (test_publisher_, header.stamp );
78
94
rclcpp::spin_some (node_);
95
+
96
+ // Check if the published_time_ is created
79
97
ASSERT_TRUE (published_time_ != nullptr );
80
98
81
99
// Check if the published time is the same as the header
0 commit comments