Skip to content

Commit 4abe9a7

Browse files
committed
feat(published_time_publisher): add unit test
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 3ba1ecd commit 4abe9a7

File tree

1 file changed

+81
-0
lines changed

1 file changed

+81
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
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 PublishedTimePublisherTest : 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_{nullptr};
28+
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> test_publisher_{nullptr};
29+
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
30+
test_subscriber_{nullptr};
31+
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr published_time_{nullptr};
32+
33+
void SetUp() override
34+
{
35+
ASSERT_TRUE(rclcpp::ok());
36+
37+
// Create a node
38+
node_ = std::make_shared<rclcpp::Node>("PublishedTimePublisher_test_node");
39+
// Create a publisher
40+
test_publisher_ =
41+
node_->create_publisher<std_msgs::msg::Header>("PublishedTimePublisher_test_topic", 1);
42+
// Create a PublishedTimePublisher
43+
published_time_publisher_ =
44+
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());
45+
// Create a subscriber
46+
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;
50+
});
51+
rclcpp::spin_some(node_);
52+
}
53+
54+
void TearDown() override {}
55+
};
56+
57+
TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
58+
{
59+
std_msgs::msg::Header header;
60+
header.stamp = rclcpp::Time(1234);
61+
62+
// Use Published Time Publisher with a timestamp
63+
published_time_publisher_->publish(test_publisher_, header);
64+
rclcpp::spin_some(node_);
65+
66+
// Check if the published time is the same as the header
67+
EXPECT_EQ(published_time_->header.stamp, header.stamp);
68+
}
69+
70+
TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
71+
{
72+
std_msgs::msg::Header header;
73+
header.stamp = rclcpp::Time(4321);
74+
75+
// Use Published Time Publisher with a timestamp
76+
published_time_publisher_->publish(test_publisher_, header.stamp);
77+
rclcpp::spin_some(node_);
78+
79+
// Check if the published time is the same as the header
80+
EXPECT_EQ(published_time_->header.stamp, header.stamp);
81+
}

0 commit comments

Comments
 (0)