Skip to content

Commit 36731c2

Browse files
committed
feat(tier4_autoware_utils): add published time debug class into utils
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 3caa2e3 commit 36731c2

File tree

2 files changed

+133
-0
lines changed

2 files changed

+133
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,132 @@
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(
66+
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
67+
{
68+
const auto & gid = publisher->get_gid();
69+
const auto & topic_name = publisher->get_topic_name();
70+
71+
// if the publisher is not in the map, create a new publisher for published time
72+
if (publishers_.find(gid) == publishers_.end()) {
73+
publishers_[gid] = node_->create_publisher<PublishedTime>(
74+
static_cast<std::string>(topic_name) + end_name_, qos_);
75+
}
76+
77+
const auto & pub_published_time_ = publishers_[gid];
78+
79+
// Check if there are any subscribers, otherwise don't do anything
80+
if (pub_published_time_->get_subscription_count() > 0) {
81+
PublishedTime published_time;
82+
83+
published_time.header.stamp = stamp;
84+
published_time.published_stamp = rclcpp::Clock().now();
85+
86+
pub_published_time_->publish(published_time);
87+
}
88+
}
89+
90+
void publish(
91+
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
92+
{
93+
const auto & gid = publisher->get_gid();
94+
const auto & topic_name = publisher->get_topic_name();
95+
96+
// if the publisher is not in the map, create a new publisher for published time
97+
if (publishers_.find(gid) == publishers_.end()) {
98+
publishers_[gid] = node_->create_publisher<PublishedTime>(
99+
static_cast<std::string>(topic_name) + end_name_, qos_);
100+
}
101+
102+
const auto & pub_published_time_ = publishers_[gid];
103+
104+
// Check if there are any subscribers, otherwise don't do anything
105+
if (pub_published_time_->get_subscription_count() > 0) {
106+
PublishedTime published_time;
107+
108+
published_time.header = header;
109+
published_time.published_stamp = rclcpp::Clock().now();
110+
111+
pub_published_time_->publish(published_time);
112+
}
113+
}
114+
115+
private:
116+
explicit PublishedTimePublisher(
117+
rclcpp::Node * node, const std::string & end_name, const rclcpp::QoS & qos)
118+
: node_(node), end_name_(end_name), qos_(qos)
119+
{
120+
}
121+
122+
rclcpp::Node * node_;
123+
std::string end_name_;
124+
rclcpp::QoS qos_;
125+
126+
// store them for each different publisher of the node
127+
std::unordered_map<rmw_gid_t, rclcpp::Publisher<PublishedTime>::SharedPtr, GidHash, GidEqual>
128+
publishers_;
129+
};
130+
} // namespace tier4_autoware_utils
131+
132+
#endif // TIER4_AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_

common/tier4_autoware_utils/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
<depend>autoware_auto_perception_msgs</depend>
1616
<depend>autoware_auto_planning_msgs</depend>
1717
<depend>autoware_auto_vehicle_msgs</depend>
18+
<depend>autoware_internal_msgs</depend>
1819
<depend>builtin_interfaces</depend>
1920
<depend>diagnostic_msgs</depend>
2021
<depend>geometry_msgs</depend>

0 commit comments

Comments
 (0)