Skip to content

Commit b42b772

Browse files
committed
feat: move GidCompare and namespace into class
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 37dd014 commit b42b772

File tree

1 file changed

+18
-18
lines changed

1 file changed

+18
-18
lines changed

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

+18-18
Original file line numberDiff line numberDiff line change
@@ -26,34 +26,23 @@
2626

2727
namespace tier4_autoware_utils
2828
{
29-
using autoware_internal_msgs::msg::PublishedTime;
30-
31-
// Custom comparison struct for rmw_gid_t
32-
struct GidCompare
33-
{
34-
bool operator()(const rmw_gid_t & lhs, const rmw_gid_t & rhs) const
35-
{
36-
return std::memcmp(lhs.data, rhs.data, RMW_GID_STORAGE_SIZE) < 0;
37-
}
38-
};
3929

4030
class PublishedTimePublisher
4131
{
4232
public:
4333
explicit PublishedTimePublisher(
44-
rclcpp::Node * node, const std::string & end_name = "/debug/published_time",
34+
rclcpp::Node * node, const std::string & publisher_topic_suffix = "/debug/published_time",
4535
const rclcpp::QoS & qos = rclcpp::QoS(1))
46-
: node_(node), end_name_(end_name), qos_(qos)
36+
: node_(node), publisher_topic_suffix_(publisher_topic_suffix), qos_(qos)
4737
{
4838
}
4939

5040
void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
5141
{
5242
const auto & gid_key = publisher->get_gid();
53-
const auto & topic_name = publisher->get_topic_name();
5443

5544
// if the publisher is not in the map, create a new publisher for published time
56-
ensure_publisher_exists(gid_key, topic_name);
45+
ensure_publisher_exists(gid_key, publisher->get_topic_name());
5746

5847
const auto & pub_published_time_ = publishers_[gid_key];
5948

@@ -72,10 +61,9 @@ class PublishedTimePublisher
7261
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
7362
{
7463
const auto & gid_key = publisher->get_gid();
75-
const auto & topic_name = publisher->get_topic_name();
7664

7765
// if the publisher is not in the map, create a new publisher for published time
78-
ensure_publisher_exists(gid_key, topic_name);
66+
ensure_publisher_exists(gid_key, publisher->get_topic_name());
7967

8068
const auto & pub_published_time_ = publishers_[gid_key];
8169

@@ -92,14 +80,26 @@ class PublishedTimePublisher
9280

9381
private:
9482
rclcpp::Node * node_;
95-
std::string end_name_;
83+
std::string publisher_topic_suffix_;
9684
rclcpp::QoS qos_;
9785

86+
using PublishedTime = autoware_internal_msgs::msg::PublishedTime;
87+
88+
// Custom comparison struct for rmw_gid_t
89+
struct GidCompare
90+
{
91+
bool operator()(const rmw_gid_t & lhs, const rmw_gid_t & rhs) const
92+
{
93+
return std::memcmp(lhs.data, rhs.data, RMW_GID_STORAGE_SIZE) < 0;
94+
}
95+
};
96+
9897
// ensure that the publisher exists in publisher_ map, if not, create a new one
9998
void ensure_publisher_exists(const rmw_gid_t & gid_key, const std::string & topic_name)
10099
{
101100
if (publishers_.find(gid_key) == publishers_.end()) {
102-
publishers_[gid_key] = node_->create_publisher<PublishedTime>(topic_name + end_name_, qos_);
101+
publishers_[gid_key] =
102+
node_->create_publisher<PublishedTime>(topic_name + publisher_topic_suffix_, qos_);
103103
}
104104
}
105105

0 commit comments

Comments
 (0)