@@ -28,52 +28,34 @@ namespace tier4_autoware_utils
28
28
{
29
29
using autoware_internal_msgs::msg::PublishedTime;
30
30
31
- struct GidHash
31
+ // Custom comparison struct for rmw_gid_t
32
+ struct GidCompare
32
33
{
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
34
35
{
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 ;
46
37
}
47
38
};
48
39
49
40
class PublishedTimePublisher
50
41
{
51
42
public:
52
- static std::unique_ptr< PublishedTimePublisher> create (
43
+ explicit PublishedTimePublisher (
53
44
rclcpp::Node * node, const std::string & end_name = " /debug/published_time" ,
54
45
const rclcpp::QoS & qos = rclcpp::QoS(1 ))
46
+ : node_(node), end_name_(end_name), qos_(qos)
55
47
{
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
48
}
64
49
65
50
void publish (const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
66
51
{
67
- const auto & gid = publisher->get_gid ();
52
+ const auto & gid_key = publisher->get_gid ();
68
53
const auto & topic_name = publisher->get_topic_name ();
69
54
70
55
// 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);
75
57
76
- const auto & pub_published_time_ = publishers_[gid ];
58
+ const auto & pub_published_time_ = publishers_[gid_key ];
77
59
78
60
// Check if there are any subscribers, otherwise don't do anything
79
61
if (pub_published_time_->get_subscription_count () > 0 ) {
@@ -89,16 +71,13 @@ class PublishedTimePublisher
89
71
void publish (
90
72
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
91
73
{
92
- const auto & gid = publisher->get_gid ();
74
+ const auto & gid_key = publisher->get_gid ();
93
75
const auto & topic_name = publisher->get_topic_name ();
94
76
95
77
// 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);
100
79
101
- const auto & pub_published_time_ = publishers_[gid ];
80
+ const auto & pub_published_time_ = publishers_[gid_key ];
102
81
103
82
// Check if there are any subscribers, otherwise don't do anything
104
83
if (pub_published_time_->get_subscription_count () > 0 ) {
@@ -112,19 +91,20 @@ class PublishedTimePublisher
112
91
}
113
92
114
93
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
94
rclcpp::Node * node_;
122
95
std::string end_name_;
123
96
rclcpp::QoS qos_;
124
97
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
+
125
106
// 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_;
128
108
};
129
109
} // namespace tier4_autoware_utils
130
110
0 commit comments