diff --git a/common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp b/common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp new file mode 100644 index 0000000000000..751c5f12060a9 --- /dev/null +++ b/common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp @@ -0,0 +1,81 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include +#include + +#include + +class PublishedTimePublisherTest : public ::testing::Test +{ +protected: + std::shared_ptr node_{nullptr}; + std::shared_ptr published_time_publisher_{nullptr}; + std::shared_ptr> test_publisher_{nullptr}; + std::shared_ptr> + test_subscriber_{nullptr}; + autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr published_time_{nullptr}; + + void SetUp() override + { + ASSERT_TRUE(rclcpp::ok()); + + // Create a node + node_ = std::make_shared("PublishedTimePublisher_test_node"); + // Create a publisher + test_publisher_ = + node_->create_publisher("PublishedTimePublisher_test_topic", 1); + // Create a PublishedTimePublisher + published_time_publisher_ = + std::make_shared(node_.get()); + // Create a subscriber + test_subscriber_ = node_->create_subscription( + "PublishedTimePublisher_test_topic/debug/published_time", 1, + [this](autoware_internal_msgs::msg::PublishedTime::SharedPtr msg) { + this->published_time_ = msg; + }); + rclcpp::spin_some(node_); + } + + void TearDown() override {} +}; + +TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader) +{ + std_msgs::msg::Header header; + header.stamp = rclcpp::Time(1234); + + // Use Published Time Publisher with a timestamp + published_time_publisher_->publish(test_publisher_, header); + rclcpp::spin_some(node_); + + // Check if the published time is the same as the header + EXPECT_EQ(published_time_->header.stamp, header.stamp); +} + +TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp) +{ + std_msgs::msg::Header header; + header.stamp = rclcpp::Time(4321); + + // Use Published Time Publisher with a timestamp + published_time_publisher_->publish(test_publisher_, header.stamp); + rclcpp::spin_some(node_); + + // Check if the published time is the same as the header + EXPECT_EQ(published_time_->header.stamp, header.stamp); +}