|
| 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 | +#ifndef TIER4_AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ |
| 16 | +#define TIER4_AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ |
| 17 | + |
| 18 | +#include <rclcpp/rclcpp.hpp> |
| 19 | + |
| 20 | +#include <autoware_internal_msgs/msg/published_time.hpp> |
| 21 | +#include <std_msgs/msg/header.hpp> |
| 22 | + |
| 23 | +#include <functional> |
| 24 | +#include <map> |
| 25 | +#include <string> |
| 26 | + |
| 27 | +namespace tier4_autoware_utils |
| 28 | +{ |
| 29 | +using autoware_internal_msgs::msg::PublishedTime; |
| 30 | + |
| 31 | +struct GidHash |
| 32 | +{ |
| 33 | + size_t operator()(const rmw_gid_t & gid) const noexcept |
| 34 | + { |
| 35 | + // Hashing function that computes a hash value for the GID |
| 36 | + std::hash<std::string> hasher; |
| 37 | + return hasher(std::string(reinterpret_cast<const char *>(gid.data), RMW_GID_STORAGE_SIZE)); |
| 38 | + } |
| 39 | +}; |
| 40 | + |
| 41 | +struct GidEqual |
| 42 | +{ |
| 43 | + bool operator()(const rmw_gid_t & lhs, const rmw_gid_t & rhs) const noexcept |
| 44 | + { |
| 45 | + return std::memcmp(lhs.data, rhs.data, RMW_GID_STORAGE_SIZE) == 0; |
| 46 | + } |
| 47 | +}; |
| 48 | + |
| 49 | +class PublishedTimePublisher |
| 50 | +{ |
| 51 | +public: |
| 52 | + static std::unique_ptr<PublishedTimePublisher> create( |
| 53 | + rclcpp::Node * node, const std::string & end_name = "/debug/published_time", |
| 54 | + const rclcpp::QoS & qos = rclcpp::QoS(1)) |
| 55 | + { |
| 56 | + const bool use_published_time = node->declare_parameter<bool>("use_published_time", false); |
| 57 | + if (use_published_time) { |
| 58 | + return std::unique_ptr<PublishedTimePublisher>( |
| 59 | + new PublishedTimePublisher(node, end_name, qos)); |
| 60 | + } else { |
| 61 | + return nullptr; |
| 62 | + } |
| 63 | + } |
| 64 | + |
| 65 | + void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp) |
| 66 | + { |
| 67 | + const auto & gid = publisher->get_gid(); |
| 68 | + const auto & topic_name = publisher->get_topic_name(); |
| 69 | + |
| 70 | + // if the publisher is not in the map, create a new publisher for published time |
| 71 | + if (publishers_.find(gid) == publishers_.end()) { |
| 72 | + publishers_[gid] = node_->create_publisher<PublishedTime>( |
| 73 | + static_cast<std::string>(topic_name) + end_name_, qos_); |
| 74 | + } |
| 75 | + |
| 76 | + const auto & pub_published_time_ = publishers_[gid]; |
| 77 | + |
| 78 | + // Check if there are any subscribers, otherwise don't do anything |
| 79 | + if (pub_published_time_->get_subscription_count() > 0) { |
| 80 | + PublishedTime published_time; |
| 81 | + |
| 82 | + published_time.header.stamp = stamp; |
| 83 | + published_time.published_stamp = rclcpp::Clock().now(); |
| 84 | + |
| 85 | + pub_published_time_->publish(published_time); |
| 86 | + } |
| 87 | + } |
| 88 | + |
| 89 | + void publish( |
| 90 | + const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header) |
| 91 | + { |
| 92 | + const auto & gid = publisher->get_gid(); |
| 93 | + const auto & topic_name = publisher->get_topic_name(); |
| 94 | + |
| 95 | + // if the publisher is not in the map, create a new publisher for published time |
| 96 | + if (publishers_.find(gid) == publishers_.end()) { |
| 97 | + publishers_[gid] = node_->create_publisher<PublishedTime>( |
| 98 | + static_cast<std::string>(topic_name) + end_name_, qos_); |
| 99 | + } |
| 100 | + |
| 101 | + const auto & pub_published_time_ = publishers_[gid]; |
| 102 | + |
| 103 | + // Check if there are any subscribers, otherwise don't do anything |
| 104 | + if (pub_published_time_->get_subscription_count() > 0) { |
| 105 | + PublishedTime published_time; |
| 106 | + |
| 107 | + published_time.header = header; |
| 108 | + published_time.published_stamp = rclcpp::Clock().now(); |
| 109 | + |
| 110 | + pub_published_time_->publish(published_time); |
| 111 | + } |
| 112 | + } |
| 113 | + |
| 114 | +private: |
| 115 | + explicit PublishedTimePublisher( |
| 116 | + rclcpp::Node * node, const std::string & end_name, const rclcpp::QoS & qos) |
| 117 | + : node_(node), end_name_(end_name), qos_(qos) |
| 118 | + { |
| 119 | + } |
| 120 | + |
| 121 | + rclcpp::Node * node_; |
| 122 | + std::string end_name_; |
| 123 | + rclcpp::QoS qos_; |
| 124 | + |
| 125 | + // store them for each different publisher of the node |
| 126 | + std::unordered_map<rmw_gid_t, rclcpp::Publisher<PublishedTime>::SharedPtr, GidHash, GidEqual> |
| 127 | + publishers_; |
| 128 | +}; |
| 129 | +} // namespace tier4_autoware_utils |
| 130 | + |
| 131 | +#endif // TIER4_AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ |
0 commit comments