diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp index b7ae50bcde1db..21705cab9a962 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp @@ -24,6 +24,7 @@ #include #include #include +#include namespace tier4_autoware_utils { @@ -32,9 +33,9 @@ class PublishedTimePublisher { public: explicit PublishedTimePublisher( - rclcpp::Node * node, const std::string & publisher_topic_suffix = "/debug/published_time", + rclcpp::Node * node, std::string publisher_topic_suffix = "/debug/published_time", const rclcpp::QoS & qos = rclcpp::QoS(1)) - : node_(node), publisher_topic_suffix_(publisher_topic_suffix), qos_(qos) + : node_(node), publisher_topic_suffix_(std::move(publisher_topic_suffix)), qos_(qos) { } @@ -46,16 +47,16 @@ class PublishedTimePublisher // if the publisher is not in the map, create a new publisher for published time ensure_publisher_exists(gid_key, publisher->get_topic_name()); - const auto & pub_published_time_ = publishers_[gid_key]; + const auto & pub_published_time = publishers_[gid_key]; // Check if there are any subscribers, otherwise don't do anything - if (pub_published_time_->get_subscription_count() > 0) { + if (pub_published_time->get_subscription_count() > 0) { PublishedTime published_time; published_time.header.stamp = stamp; published_time.published_stamp = rclcpp::Clock().now(); - pub_published_time_->publish(published_time); + pub_published_time->publish(published_time); } } @@ -67,16 +68,16 @@ class PublishedTimePublisher // if the publisher is not in the map, create a new publisher for published time ensure_publisher_exists(gid_key, publisher->get_topic_name()); - const auto & pub_published_time_ = publishers_[gid_key]; + const auto & pub_published_time = publishers_[gid_key]; // Check if there are any subscribers, otherwise don't do anything - if (pub_published_time_->get_subscription_count() > 0) { + if (pub_published_time->get_subscription_count() > 0) { PublishedTime published_time; published_time.header = header; published_time.published_stamp = rclcpp::Clock().now(); - pub_published_time_->publish(published_time); + pub_published_time->publish(published_time); } }