@@ -25,10 +25,17 @@ class PublishedTimePublisherTest : public ::testing::Test
25
25
protected:
26
26
std::shared_ptr<rclcpp::Node> node_{nullptr };
27
27
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 };
29
34
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 };
32
39
33
40
void SetUp () override
34
41
{
@@ -37,25 +44,39 @@ class PublishedTimePublisherTest : public ::testing::Test
37
44
// Simplify node and topic names for brevity and uniqueness
38
45
const std::string test_name = ::testing::UnitTest::GetInstance ()->current_test_info ()->name ();
39
46
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
42
49
43
50
// Create a node
44
51
node_ = std::make_shared<rclcpp::Node>(base_name + " _node" );
45
52
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 );
48
60
49
61
// Create a PublishedTimePublisher
50
62
published_time_publisher_ =
51
63
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get ());
52
64
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 ,
56
68
[this ](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
57
- this ->published_time_ = std::move (msg);
69
+ this ->first_published_time_ = std::move (msg);
58
70
});
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
+
59
80
rclcpp::spin_some (node_);
60
81
}
61
82
@@ -70,15 +91,15 @@ TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
70
91
std_msgs::msg::Header header;
71
92
header.stamp = rclcpp::Time (1234 );
72
93
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);
75
96
rclcpp::spin_some (node_);
76
97
77
98
// Check if the published_time_ is created
78
- ASSERT_TRUE (published_time_ != nullptr );
99
+ ASSERT_TRUE (first_published_time_ != nullptr );
79
100
80
101
// 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 );
82
103
}
83
104
84
105
TEST_F (PublishedTimePublisherTest, PublishMsgWithTimestamp)
@@ -89,13 +110,57 @@ TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
89
110
std_msgs::msg::Header header;
90
111
header.stamp = rclcpp::Time (4321 );
91
112
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 );
94
157
rclcpp::spin_some (node_);
95
158
96
159
// 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 );
98
162
99
163
// 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 );
101
166
}
0 commit comments