24
24
#include < functional>
25
25
#include < map>
26
26
#include < string>
27
+ #include < utility>
27
28
28
29
namespace tier4_autoware_utils
29
30
{
@@ -32,9 +33,9 @@ class PublishedTimePublisher
32
33
{
33
34
public:
34
35
explicit PublishedTimePublisher (
35
- rclcpp::Node * node, const std::string & publisher_topic_suffix = " /debug/published_time" ,
36
+ rclcpp::Node * node, std::string publisher_topic_suffix = " /debug/published_time" ,
36
37
const rclcpp::QoS & qos = rclcpp::QoS(1 ))
37
- : node_(node), publisher_topic_suffix_(publisher_topic_suffix), qos_(qos)
38
+ : node_(node), publisher_topic_suffix_(std::move( publisher_topic_suffix) ), qos_(qos)
38
39
{
39
40
}
40
41
@@ -46,16 +47,16 @@ class PublishedTimePublisher
46
47
// if the publisher is not in the map, create a new publisher for published time
47
48
ensure_publisher_exists (gid_key, publisher->get_topic_name ());
48
49
49
- const auto & pub_published_time_ = publishers_[gid_key];
50
+ const auto & pub_published_time = publishers_[gid_key];
50
51
51
52
// Check if there are any subscribers, otherwise don't do anything
52
- if (pub_published_time_ ->get_subscription_count () > 0 ) {
53
+ if (pub_published_time ->get_subscription_count () > 0 ) {
53
54
PublishedTime published_time;
54
55
55
56
published_time.header .stamp = stamp;
56
57
published_time.published_stamp = rclcpp::Clock ().now ();
57
58
58
- pub_published_time_ ->publish (published_time);
59
+ pub_published_time ->publish (published_time);
59
60
}
60
61
}
61
62
@@ -67,16 +68,16 @@ class PublishedTimePublisher
67
68
// if the publisher is not in the map, create a new publisher for published time
68
69
ensure_publisher_exists (gid_key, publisher->get_topic_name ());
69
70
70
- const auto & pub_published_time_ = publishers_[gid_key];
71
+ const auto & pub_published_time = publishers_[gid_key];
71
72
72
73
// Check if there are any subscribers, otherwise don't do anything
73
- if (pub_published_time_ ->get_subscription_count () > 0 ) {
74
+ if (pub_published_time ->get_subscription_count () > 0 ) {
74
75
PublishedTime published_time;
75
76
76
77
published_time.header = header;
77
78
published_time.published_stamp = rclcpp::Clock ().now ();
78
79
79
- pub_published_time_ ->publish (published_time);
80
+ pub_published_time ->publish (published_time);
80
81
}
81
82
}
82
83
0 commit comments