20
20
21
21
#include < gtest/gtest.h>
22
22
23
- class PublishedTimePublisherTest : public ::testing::Test
23
+ class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test
24
24
{
25
25
protected:
26
26
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 };
28
29
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 };
31
32
32
33
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
33
- first_test_subscriber_ {nullptr };
34
+ first_test_subscriber_ptr_ {nullptr };
34
35
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
35
- second_test_subscriber_ {nullptr };
36
+ second_test_subscriber_ptr_ {nullptr };
36
37
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_;
39
43
40
44
void SetUp () override
41
45
{
42
46
ASSERT_TRUE (rclcpp::ok ());
43
47
48
+ // init headers which will be used to publish
49
+ first_header_.stamp = rclcpp::Time (0 );
50
+ first_header_.frame_id = " frame_id_1" ;
51
+ second_header_.stamp = rclcpp::Time (1 );
52
+ second_header_.frame_id = " frame_id_2" ;
53
+
44
54
// Simplify node and topic names for brevity and uniqueness
45
55
const std::string test_name = ::testing::UnitTest::GetInstance ()->current_test_info ()->name ();
46
56
const std::string base_name =
@@ -51,30 +61,31 @@ class PublishedTimePublisherTest : public ::testing::Test
51
61
node_ = std::make_shared<rclcpp::Node>(base_name + " _node" );
52
62
53
63
// Create the first publisher
54
- first_test_publisher_ =
64
+ first_test_publisher_ptr_ =
55
65
node_->create_publisher <std_msgs::msg::Header>(base_name + " _topic1" , 1 );
56
66
57
67
// Create the second publisher
58
- second_test_publisher_ =
68
+ second_test_publisher_ptr_ =
59
69
node_->create_publisher <std_msgs::msg::Header>(base_name + " _topic2" , 1 );
60
70
61
71
// Create a PublishedTimePublisher
62
- published_time_publisher_ =
72
+ published_time_publisher_ptr_ =
63
73
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get ());
64
74
65
75
// 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
+ });
71
82
72
83
// Create the second subscriber
73
- second_test_subscriber_ =
84
+ second_test_subscriber_ptr_ =
74
85
node_->create_subscription <autoware_internal_msgs::msg::PublishedTime>(
75
86
base_name + " _topic2" + suffix, 1 ,
76
87
[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);
78
89
});
79
90
80
91
rclcpp::spin_some (node_);
@@ -83,84 +94,233 @@ class PublishedTimePublisherTest : public ::testing::Test
83
94
void TearDown () override {}
84
95
};
85
96
86
- TEST_F (PublishedTimePublisherTest, PublishMsgWithHeader)
97
+ class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test
87
98
{
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 };
106
+
107
+ autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_ptr_{nullptr };
108
+ autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_ptr_{nullptr };
109
+
110
+ std_msgs::msg::Header first_header_;
111
+ std_msgs::msg::Header second_header_;
112
+
113
+ void SetUp () override
114
+ {
115
+ ASSERT_TRUE (rclcpp::ok ());
116
+
117
+ // init headers which will be used to publish
118
+ first_header_.stamp = rclcpp::Time (0 );
119
+ first_header_.frame_id = " frame_id_1" ;
120
+ second_header_.stamp = rclcpp::Time (1 );
121
+ second_header_.frame_id = " frame_id_2" ;
122
+
123
+ // Simplify node and topic names for brevity and uniqueness
124
+ const std::string test_name = ::testing::UnitTest::GetInstance ()->current_test_info ()->name ();
125
+ const std::string base_name =
126
+ " published_time_publisher_" + test_name; // Base name for node and topics
127
+ const std::string suffix = " /debug/published_time" ; // Suffix for published time topics
128
+
129
+ // Create a node
130
+ node_ = std::make_shared<rclcpp::Node>(base_name + " _node" );
131
+
132
+ // Create the first publisher
133
+ first_test_publisher_ptr_ =
134
+ node_->create_publisher <std_msgs::msg::Header>(base_name + " _topic1" , 1 );
135
+
136
+ // Create the second publisher
137
+ second_test_publisher_ptr_ =
138
+ node_->create_publisher <std_msgs::msg::Header>(base_name + " _topic2" , 1 );
139
+
140
+ // Create a PublishedTimePublisher
141
+ published_time_publisher_ptr_ =
142
+ std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get ());
143
+
144
+ rclcpp::spin_some (node_);
145
+ }
146
+
147
+ void TearDown () override {}
148
+ };
90
149
91
- std_msgs::msg::Header header;
92
- header.stamp = rclcpp::Time (1234 );
150
+ TEST_F (PublishedTimePublisherWithSubscriptionTest, WithoutPublishing)
151
+ {
152
+ // Check if the PublishedTimePublisher is created
153
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
93
154
94
155
// Use Published Time Publisher .publish_if_subscribed() with a header
95
- published_time_publisher_ ->publish_if_subscribed (first_test_publisher_, header );
156
+ published_time_publisher_ptr_ ->publish_if_subscribed (first_test_publisher_ptr_, first_header_ );
96
157
rclcpp::spin_some (node_);
97
158
98
159
// Check if the published_time_ is created
99
- ASSERT_TRUE (first_published_time_ != nullptr );
160
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
100
161
101
162
// Check if the published time is the same as the header
102
- EXPECT_EQ (first_published_time_ ->header .stamp , header .stamp );
163
+ EXPECT_EQ (first_published_time_ptr_ ->header .stamp , first_header_ .stamp );
103
164
}
104
165
105
- TEST_F (PublishedTimePublisherTest, PublishMsgWithTimestamp )
166
+ TEST_F (PublishedTimePublisherWithSubscriptionTest, PublishMsgWithHeader )
106
167
{
107
168
// Check if the PublishedTimePublisher is created
108
- ASSERT_TRUE (published_time_publisher_ != nullptr );
169
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
109
170
110
- std_msgs::msg::Header header;
111
- header.stamp = rclcpp::Time (4321 );
171
+ // Use Published Time Publisher .publish_if_subscribed() with a header
172
+ published_time_publisher_ptr_->publish_if_subscribed (first_test_publisher_ptr_, first_header_);
173
+ rclcpp::spin_some (node_);
174
+
175
+ // Check if the published_time_ is created
176
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
177
+
178
+ // Check if the published time is the same as the header
179
+ EXPECT_EQ (first_published_time_ptr_->header .stamp , first_header_.stamp );
180
+ }
181
+
182
+ TEST_F (PublishedTimePublisherWithSubscriptionTest, PublishMsgWithTimestamp)
183
+ {
184
+ // Check if the PublishedTimePublisher is created
185
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
112
186
113
187
// Use Published Time Publisher .publish_if_subscribed() with a timestamp
114
- published_time_publisher_->publish_if_subscribed (first_test_publisher_, header.stamp );
188
+ published_time_publisher_ptr_->publish_if_subscribed (
189
+ first_test_publisher_ptr_, first_header_.stamp );
115
190
rclcpp::spin_some (node_);
116
191
117
192
// Check if the published_time_ is created
118
- ASSERT_TRUE (first_published_time_ != nullptr );
193
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
119
194
120
195
// Check if the published time is the same as the header
121
- EXPECT_EQ (first_published_time_ ->header .stamp , header .stamp );
196
+ EXPECT_EQ (first_published_time_ptr_ ->header .stamp , first_header_ .stamp );
122
197
}
123
198
124
- TEST_F (PublishedTimePublisherTest , MultiplePublishMsgWithHeader)
199
+ TEST_F (PublishedTimePublisherWithSubscriptionTest , MultiplePublishMsgWithHeader)
125
200
{
126
201
// 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 );
202
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
131
203
132
204
// 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 );
205
+ published_time_publisher_ptr_ ->publish_if_subscribed (first_test_publisher_ptr_, first_header_ );
206
+ published_time_publisher_ptr_ ->publish_if_subscribed (second_test_publisher_ptr_, first_header_ );
135
207
rclcpp::spin_some (node_);
136
208
137
209
// Check if the published_time_ is created
138
- ASSERT_TRUE (first_published_time_ != nullptr );
139
- ASSERT_TRUE (second_published_time_ != nullptr );
210
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
211
+ ASSERT_TRUE (second_published_time_ptr_ != nullptr );
140
212
141
213
// 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 );
214
+ EXPECT_EQ (first_published_time_ptr_ ->header .stamp , first_header_ .stamp );
215
+ EXPECT_EQ (second_published_time_ptr_ ->header .stamp , first_header_ .stamp );
144
216
}
145
217
146
- TEST_F (PublishedTimePublisherTest , MultiplePublishMsgWithTimestamp)
218
+ TEST_F (PublishedTimePublisherWithSubscriptionTest , MultiplePublishMsgWithTimestamp)
147
219
{
148
220
// 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 );
221
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
153
222
154
223
// 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 );
224
+ published_time_publisher_ptr_->publish_if_subscribed (
225
+ first_test_publisher_ptr_, first_header_.stamp );
226
+ published_time_publisher_ptr_->publish_if_subscribed (
227
+ second_test_publisher_ptr_, first_header_.stamp );
157
228
rclcpp::spin_some (node_);
158
229
159
230
// Check if the published_time_ is created
160
- ASSERT_TRUE (first_published_time_ != nullptr );
161
- ASSERT_TRUE (second_published_time_ != nullptr );
231
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
232
+ ASSERT_TRUE (second_published_time_ptr_ != nullptr );
162
233
163
234
// 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 );
235
+ EXPECT_EQ (first_published_time_ptr_->header .stamp , first_header_.stamp );
236
+ EXPECT_EQ (second_published_time_ptr_->header .stamp , first_header_.stamp );
237
+ }
238
+
239
+ TEST_F (PublishedTimePublisherWithoutSubscriptionTest, WithoutPublishing)
240
+ {
241
+ // Check if the PublishedTimePublisher is created
242
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
243
+
244
+ // Use Published Time Publisher .publish_if_subscribed() with a header
245
+ published_time_publisher_ptr_->publish_if_subscribed (first_test_publisher_ptr_, first_header_);
246
+ rclcpp::spin_some (node_);
247
+
248
+ // Check if the published_time_ is created
249
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
250
+
251
+ // Check if the published time is null
252
+ EXPECT_EQ (first_published_time_ptr_, nullptr );
253
+ }
254
+
255
+ TEST_F (PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithHeader)
256
+ {
257
+ // Check if the PublishedTimePublisher is created
258
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
259
+
260
+ // Use Published Time Publisher .publish_if_subscribed() with a header
261
+ published_time_publisher_ptr_->publish_if_subscribed (first_test_publisher_ptr_, first_header_);
262
+ rclcpp::spin_some (node_);
263
+
264
+ // Check if the published_time_ is created
265
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
266
+
267
+ // Check if the published time is null
268
+ EXPECT_EQ (first_published_time_ptr_, nullptr );
269
+ }
270
+
271
+ TEST_F (PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithTimestamp)
272
+ {
273
+ // Check if the PublishedTimePublisher is created
274
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
275
+
276
+ // Use Published Time Publisher .publish_if_subscribed() with a timestamp
277
+ published_time_publisher_ptr_->publish_if_subscribed (
278
+ first_test_publisher_ptr_, first_header_.stamp );
279
+ rclcpp::spin_some (node_);
280
+
281
+ // Check if the published_time_ is created
282
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
283
+
284
+ // Check if the published time is null
285
+ EXPECT_EQ (first_published_time_ptr_, nullptr );
286
+ }
287
+
288
+ TEST_F (PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithHeader)
289
+ {
290
+ // Check if the PublishedTimePublisher is created
291
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
292
+
293
+ // Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
294
+ published_time_publisher_ptr_->publish_if_subscribed (first_test_publisher_ptr_, first_header_);
295
+ published_time_publisher_ptr_->publish_if_subscribed (second_test_publisher_ptr_, first_header_);
296
+ rclcpp::spin_some (node_);
297
+
298
+ // Check if the published_time_ is created
299
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
300
+ ASSERT_TRUE (second_published_time_ptr_ != nullptr );
301
+
302
+ // Check if the published time is null
303
+ EXPECT_EQ (first_published_time_ptr_, nullptr );
304
+ EXPECT_EQ (second_published_time_ptr_, nullptr );
305
+ }
306
+
307
+ TEST_F (PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithTimestamp)
308
+ {
309
+ // Check if the PublishedTimePublisher is created
310
+ ASSERT_TRUE (published_time_publisher_ptr_ != nullptr );
311
+
312
+ // Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
313
+ published_time_publisher_ptr_->publish_if_subscribed (
314
+ first_test_publisher_ptr_, first_header_.stamp );
315
+ published_time_publisher_ptr_->publish_if_subscribed (
316
+ second_test_publisher_ptr_, first_header_.stamp );
317
+ rclcpp::spin_some (node_);
318
+
319
+ // Check if the published_time_ is created
320
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
321
+ ASSERT_TRUE (second_published_time_ptr_ != nullptr );
322
+
323
+ // Check if the published time is null
324
+ EXPECT_EQ (first_published_time_ptr_, nullptr );
325
+ EXPECT_EQ (second_published_time_ptr_, nullptr );
166
326
}
0 commit comments