Skip to content

Commit

Permalink
feat: update
Browse files Browse the repository at this point in the history
Signed-off-by: Berkay Karaman <[email protected]>
  • Loading branch information
brkay54 committed Mar 15, 2024
1 parent 287695c commit 7c775fa
Showing 1 changed file with 165 additions and 59 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,61 +20,72 @@

#include <gtest/gtest.h>

class PublishedTimePublisherTest : public ::testing::Test
class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test
{
protected:
std::shared_ptr<rclcpp::Node> node_{nullptr};
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_{nullptr};
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_ptr_{
nullptr};

std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_{nullptr};
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_{nullptr};
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_ptr_{nullptr};
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_ptr_{nullptr};

std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
first_test_subscriber_{nullptr};
first_test_subscriber_ptr_{nullptr};
std::shared_ptr<rclcpp::Subscription<autoware_internal_msgs::msg::PublishedTime>>
second_test_subscriber_{nullptr};
second_test_subscriber_ptr_{nullptr};

autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_{nullptr};
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_{nullptr};
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr first_published_time_ptr_{nullptr};
autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr second_published_time_ptr_{nullptr};

std_msgs::msg::Header first_header_;
std_msgs::msg::Header second_header_;

void SetUp() override
{
ASSERT_TRUE(rclcpp::ok());

// Simplify node and topic names for brevity and uniqueness
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
const std::string base_name =
"published_time_publisher_" + test_name; // Base name for node and topics
const std::string suffix = "/debug/published_time"; // Suffix for published time topics

// Create a node
// Initialize ROS node
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");

ASSERT_TRUE(rclcpp::ok());

// init headers which will be used to publish
first_header_.stamp = rclcpp::Time(0);
first_header_.frame_id = "frame_id_1";
second_header_.stamp = rclcpp::Time(1);
second_header_.frame_id = "frame_id_2";

// Create the first publisher
first_test_publisher_ =
first_test_publisher_ptr_ =
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);

// Create the second publisher
second_test_publisher_ =
second_test_publisher_ptr_ =
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);

// Create a PublishedTimePublisher
published_time_publisher_ =
published_time_publisher_ptr_ =
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());

// Create the first subscriber
first_test_subscriber_ = node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
base_name + "_topic1" + suffix, 1,
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
this->first_published_time_ = std::move(msg);
});
first_test_subscriber_ptr_ =
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
base_name + "_topic1" + suffix, 1,
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
this->first_published_time_ptr_ = std::move(msg);
});

// Create the second subscriber
second_test_subscriber_ =
second_test_subscriber_ptr_ =
node_->create_subscription<autoware_internal_msgs::msg::PublishedTime>(
base_name + "_topic2" + suffix, 1,
[this](autoware_internal_msgs::msg::PublishedTime::ConstSharedPtr msg) {
this->second_published_time_ = std::move(msg);
this->second_published_time_ptr_ = std::move(msg);
});

rclcpp::spin_some(node_);
Expand All @@ -83,84 +94,179 @@ class PublishedTimePublisherTest : public ::testing::Test
void TearDown() override {}
};

TEST_F(PublishedTimePublisherTest, PublishMsgWithHeader)
class PublishedTimePublisherWithoutSubscriptionTest : public ::testing::Test
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ != nullptr);
protected:
std::shared_ptr<rclcpp::Node> node_{nullptr};
std::shared_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_ptr_{
nullptr};

std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> first_test_publisher_ptr_{nullptr};
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Header>> second_test_publisher_ptr_{nullptr};

std_msgs::msg::Header header;
header.stamp = rclcpp::Time(1234);
std_msgs::msg::Header first_header_;
std_msgs::msg::Header second_header_;

void SetUp() override
{
// Simplify node and topic names for brevity and uniqueness
const std::string test_name = ::testing::UnitTest::GetInstance()->current_test_info()->name();
const std::string base_name =
"published_time_publisher_" + test_name; // Base name for node and topics

// Initialize ROS node
node_ = std::make_shared<rclcpp::Node>(base_name + "_node");

ASSERT_TRUE(rclcpp::ok());

// init headers which will be used to publish
first_header_.stamp = rclcpp::Time(0);
first_header_.frame_id = "frame_id_1";
second_header_.stamp = rclcpp::Time(1);
second_header_.frame_id = "frame_id_2";

// Create the first publisher
first_test_publisher_ptr_ =
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic1", 1);

// Create the second publisher
second_test_publisher_ptr_ =
node_->create_publisher<std_msgs::msg::Header>(base_name + "_topic2", 1);

// Create a PublishedTimePublisher
published_time_publisher_ptr_ =
std::make_shared<tier4_autoware_utils::PublishedTimePublisher>(node_.get());

rclcpp::spin_some(node_);
}

void TearDown() override {}
};

TEST_F(PublishedTimePublisherWithSubscriptionTest, PublishMsgWithHeader)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a header
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header);
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
rclcpp::spin_some(node_);

// Check if the published_time_ is created
ASSERT_TRUE(first_published_time_ != nullptr);
ASSERT_TRUE(first_published_time_ptr_ != nullptr);

// Check if the published time is the same as the header
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
EXPECT_EQ(first_published_time_ptr_->header.frame_id, first_header_.frame_id);
}

TEST_F(PublishedTimePublisherTest, PublishMsgWithTimestamp)
TEST_F(PublishedTimePublisherWithSubscriptionTest, PublishMsgWithTimestamp)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ != nullptr);

std_msgs::msg::Header header;
header.stamp = rclcpp::Time(4321);
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a timestamp
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header.stamp);
published_time_publisher_ptr_->publish_if_subscribed(
first_test_publisher_ptr_, first_header_.stamp);
rclcpp::spin_some(node_);

// Check if the published_time_ is created
ASSERT_TRUE(first_published_time_ != nullptr);
ASSERT_TRUE(first_published_time_ptr_ != nullptr);

// Check if the published time is the same as the header
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
EXPECT_EQ(first_published_time_ptr_->header.frame_id, std::string(""));
}

TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithHeader)
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithHeader)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ != nullptr);

std_msgs::msg::Header header;
header.stamp = rclcpp::Time(12345);
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header);
published_time_publisher_->publish_if_subscribed(second_test_publisher_, header);
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
published_time_publisher_ptr_->publish_if_subscribed(second_test_publisher_ptr_, second_header_);
rclcpp::spin_some(node_);

// Check if the published_time_ is created
ASSERT_TRUE(first_published_time_ != nullptr);
ASSERT_TRUE(second_published_time_ != nullptr);
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
ASSERT_TRUE(second_published_time_ptr_ != nullptr);

// Check if the published time is the same as the header
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
EXPECT_EQ(second_published_time_->header.stamp, header.stamp);
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
EXPECT_EQ(second_published_time_ptr_->header.stamp, second_header_.stamp);
EXPECT_EQ(first_published_time_ptr_->header.frame_id, first_header_.frame_id);
EXPECT_EQ(second_published_time_ptr_->header.frame_id, second_header_.frame_id);
}

Check warning on line 200 in common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Duplicated Assertion Blocks

The test suite contains 3 functions with duplicated assertion blocks (TEST:PublishedTimePublisherWithSubscriptionTest:MultiplePublishMsgWithHeader,TEST:PublishedTimePublisherWithSubscriptionTest:MultiplePublishMsgWithTimestamp,TEST:PublishedTimePublisherWithSubscriptionTest:PublishMsgWithTimestamp), threshold = 2. This test file has several blocks of duplicated assertion statements. Avoid adding more.

TEST_F(PublishedTimePublisherTest, MultiplePublishMsgWithTimestamp)
TEST_F(PublishedTimePublisherWithSubscriptionTest, MultiplePublishMsgWithTimestamp)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ != nullptr);

std_msgs::msg::Header header;
header.stamp = rclcpp::Time(12345);
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
published_time_publisher_->publish_if_subscribed(first_test_publisher_, header.stamp);
published_time_publisher_->publish_if_subscribed(second_test_publisher_, header.stamp);
published_time_publisher_ptr_->publish_if_subscribed(
first_test_publisher_ptr_, first_header_.stamp);
published_time_publisher_ptr_->publish_if_subscribed(
second_test_publisher_ptr_, second_header_.stamp);
rclcpp::spin_some(node_);

// Check if the published_time_ is created
ASSERT_TRUE(first_published_time_ != nullptr);
ASSERT_TRUE(second_published_time_ != nullptr);
ASSERT_TRUE(first_published_time_ptr_ != nullptr);
ASSERT_TRUE(second_published_time_ptr_ != nullptr);

// Check if the published time is the same as the header
EXPECT_EQ(first_published_time_->header.stamp, header.stamp);
EXPECT_EQ(second_published_time_->header.stamp, header.stamp);
EXPECT_EQ(first_published_time_ptr_->header.stamp, first_header_.stamp);
EXPECT_EQ(second_published_time_ptr_->header.stamp, second_header_.stamp);
EXPECT_EQ(first_published_time_ptr_->header.frame_id, std::string(""));
EXPECT_EQ(second_published_time_ptr_->header.frame_id, std::string(""));
}

TEST_F(PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithHeader)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a header
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
rclcpp::spin_some(node_);
ASSERT_TRUE(rclcpp::ok());
}

TEST_F(PublishedTimePublisherWithoutSubscriptionTest, PublishMsgWithTimestamp)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a timestamp
published_time_publisher_ptr_->publish_if_subscribed(
first_test_publisher_ptr_, first_header_.stamp);
rclcpp::spin_some(node_);
ASSERT_TRUE(rclcpp::ok());
}

TEST_F(PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithHeader)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a header for multiple publishers
published_time_publisher_ptr_->publish_if_subscribed(first_test_publisher_ptr_, first_header_);
published_time_publisher_ptr_->publish_if_subscribed(second_test_publisher_ptr_, second_header_);
rclcpp::spin_some(node_);
ASSERT_TRUE(rclcpp::ok());
}

TEST_F(PublishedTimePublisherWithoutSubscriptionTest, MultiplePublishMsgWithTimestamp)
{
// Check if the PublishedTimePublisher is created
ASSERT_TRUE(published_time_publisher_ptr_ != nullptr);

// Use Published Time Publisher .publish_if_subscribed() with a timestamp for multiple publishers
published_time_publisher_ptr_->publish_if_subscribed(
first_test_publisher_ptr_, first_header_.stamp);
published_time_publisher_ptr_->publish_if_subscribed(
second_test_publisher_ptr_, second_header_.stamp);
rclcpp::spin_some(node_);
ASSERT_TRUE(rclcpp::ok());
}

Check warning on line 272 in common/tier4_autoware_utils/test/src/ros/test_published_time_publisher.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Code Duplication

The module contains 6 functions with similar structure: TEST:PublishedTimePublisherWithSubscriptionTest:MultiplePublishMsgWithHeader,TEST:PublishedTimePublisherWithSubscriptionTest:MultiplePublishMsgWithTimestamp,TEST:PublishedTimePublisherWithSubscriptionTest:PublishMsgWithHeader,TEST:PublishedTimePublisherWithSubscriptionTest:PublishMsgWithTimestamp and 2 more functions. Avoid duplicated, aka copy-pasted, code inside the module. More duplication lowers the code health.

0 comments on commit 7c775fa

Please sign in to comment.