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
- ASSERT_TRUE (rclcpp::ok ());
43
-
44
46
// Simplify node and topic names for brevity and uniqueness
45
47
const std::string test_name = ::testing::UnitTest::GetInstance ()->current_test_info ()->name ();
46
48
const std::string base_name =
47
49
" published_time_publisher_" + test_name; // Base name for node and topics
48
50
const std::string suffix = " /debug/published_time" ; // Suffix for published time topics
49
51
50
- // Create a node
52
+ // Initialize ROS node
51
53
node_ = std::make_shared<rclcpp::Node>(base_name + " _node" );
52
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
+
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,179 @@ 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 };
90
106
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 );
93
150
94
151
// 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_ );
96
153
rclcpp::spin_some (node_);
97
154
98
155
// Check if the published_time_ is created
99
- ASSERT_TRUE (first_published_time_ != nullptr );
156
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
100
157
101
158
// 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 );
103
161
}
104
162
105
- TEST_F (PublishedTimePublisherTest , PublishMsgWithTimestamp)
163
+ TEST_F (PublishedTimePublisherWithSubscriptionTest , PublishMsgWithTimestamp)
106
164
{
107
165
// 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 );
112
167
113
168
// 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 );
115
171
rclcpp::spin_some (node_);
116
172
117
173
// Check if the published_time_ is created
118
- ASSERT_TRUE (first_published_time_ != nullptr );
174
+ ASSERT_TRUE (first_published_time_ptr_ != nullptr );
119
175
120
176
// 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 (" " ));
122
179
}
123
180
124
- TEST_F (PublishedTimePublisherTest , MultiplePublishMsgWithHeader)
181
+ TEST_F (PublishedTimePublisherWithSubscriptionTest , MultiplePublishMsgWithHeader)
125
182
{
126
183
// 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 );
131
185
132
186
// 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_ );
135
189
rclcpp::spin_some (node_);
136
190
137
191
// 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 );
140
194
141
195
// 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 );
144
200
}
145
201
146
- TEST_F (PublishedTimePublisherTest , MultiplePublishMsgWithTimestamp)
202
+ TEST_F (PublishedTimePublisherWithSubscriptionTest , MultiplePublishMsgWithTimestamp)
147
203
{
148
204
// 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 );
153
206
154
207
// 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 );
157
212
rclcpp::spin_some (node_);
158
213
159
214
// 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 );
162
217
163
218
// 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 ());
166
272
}
0 commit comments