Skip to content

Commit 37dd014

Browse files
committed
feat: remove create() function and convert unordered_map to map
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 784ae91 commit 37dd014

File tree

1 file changed

+21
-41
lines changed

1 file changed

+21
-41
lines changed

common/tier4_autoware_utils/include/tier4_autoware_utils/ros/published_time_publisher.hpp

+21-41
Original file line numberDiff line numberDiff line change
@@ -28,52 +28,34 @@ namespace tier4_autoware_utils
2828
{
2929
using autoware_internal_msgs::msg::PublishedTime;
3030

31-
struct GidHash
31+
// Custom comparison struct for rmw_gid_t
32+
struct GidCompare
3233
{
33-
size_t operator()(const rmw_gid_t & gid) const noexcept
34+
bool operator()(const rmw_gid_t & lhs, const rmw_gid_t & rhs) const
3435
{
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;
36+
return std::memcmp(lhs.data, rhs.data, RMW_GID_STORAGE_SIZE) < 0;
4637
}
4738
};
4839

4940
class PublishedTimePublisher
5041
{
5142
public:
52-
static std::unique_ptr<PublishedTimePublisher> create(
43+
explicit PublishedTimePublisher(
5344
rclcpp::Node * node, const std::string & end_name = "/debug/published_time",
5445
const rclcpp::QoS & qos = rclcpp::QoS(1))
46+
: node_(node), end_name_(end_name), qos_(qos)
5547
{
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-
}
6348
}
6449

6550
void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
6651
{
67-
const auto & gid = publisher->get_gid();
52+
const auto & gid_key = publisher->get_gid();
6853
const auto & topic_name = publisher->get_topic_name();
6954

7055
// 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-
}
56+
ensure_publisher_exists(gid_key, topic_name);
7557

76-
const auto & pub_published_time_ = publishers_[gid];
58+
const auto & pub_published_time_ = publishers_[gid_key];
7759

7860
// Check if there are any subscribers, otherwise don't do anything
7961
if (pub_published_time_->get_subscription_count() > 0) {
@@ -89,16 +71,13 @@ class PublishedTimePublisher
8971
void publish(
9072
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
9173
{
92-
const auto & gid = publisher->get_gid();
74+
const auto & gid_key = publisher->get_gid();
9375
const auto & topic_name = publisher->get_topic_name();
9476

9577
// 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-
}
78+
ensure_publisher_exists(gid_key, topic_name);
10079

101-
const auto & pub_published_time_ = publishers_[gid];
80+
const auto & pub_published_time_ = publishers_[gid_key];
10281

10382
// Check if there are any subscribers, otherwise don't do anything
10483
if (pub_published_time_->get_subscription_count() > 0) {
@@ -112,19 +91,20 @@ class PublishedTimePublisher
11291
}
11392

11493
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-
12194
rclcpp::Node * node_;
12295
std::string end_name_;
12396
rclcpp::QoS qos_;
12497

98+
// ensure that the publisher exists in publisher_ map, if not, create a new one
99+
void ensure_publisher_exists(const rmw_gid_t & gid_key, const std::string & topic_name)
100+
{
101+
if (publishers_.find(gid_key) == publishers_.end()) {
102+
publishers_[gid_key] = node_->create_publisher<PublishedTime>(topic_name + end_name_, qos_);
103+
}
104+
}
105+
125106
// store them for each different publisher of the node
126-
std::unordered_map<rmw_gid_t, rclcpp::Publisher<PublishedTime>::SharedPtr, GidHash, GidEqual>
127-
publishers_;
107+
std::map<rmw_gid_t, rclcpp::Publisher<PublishedTime>::SharedPtr, GidCompare> publishers_;
128108
};
129109
} // namespace tier4_autoware_utils
130110

0 commit comments

Comments
 (0)