Skip to content

Commit 69572f1

Browse files
authored
feat(tier4_autoware_utils): add published time debug class into utils (#6440)
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent fc2b2c6 commit 69572f1

File tree

3 files changed

+116
-0
lines changed

3 files changed

+116
-0
lines changed

build_depends.repos

+4
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,10 @@ repositories:
1616
type: git
1717
url: https://github.com/autowarefoundation/autoware_adapi_msgs.git
1818
version: main
19+
core/autoware_internal_msgs:
20+
type: git
21+
url: https://github.com/autowarefoundation/autoware_internal_msgs.git
22+
version: main
1923
core/external/autoware_auto_msgs:
2024
type: git
2125
url: https://github.com/tier4/autoware_auto_msgs.git
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,111 @@
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+
30+
class PublishedTimePublisher
31+
{
32+
public:
33+
explicit PublishedTimePublisher(
34+
rclcpp::Node * node, const std::string & publisher_topic_suffix = "/debug/published_time",
35+
const rclcpp::QoS & qos = rclcpp::QoS(1))
36+
: node_(node), publisher_topic_suffix_(publisher_topic_suffix), qos_(qos)
37+
{
38+
}
39+
40+
void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
41+
{
42+
const auto & gid_key = publisher->get_gid();
43+
44+
// if the publisher is not in the map, create a new publisher for published time
45+
ensure_publisher_exists(gid_key, publisher->get_topic_name());
46+
47+
const auto & pub_published_time_ = publishers_[gid_key];
48+
49+
// Check if there are any subscribers, otherwise don't do anything
50+
if (pub_published_time_->get_subscription_count() > 0) {
51+
PublishedTime published_time;
52+
53+
published_time.header.stamp = stamp;
54+
published_time.published_stamp = rclcpp::Clock().now();
55+
56+
pub_published_time_->publish(published_time);
57+
}
58+
}
59+
60+
void publish(
61+
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
62+
{
63+
const auto & gid_key = publisher->get_gid();
64+
65+
// if the publisher is not in the map, create a new publisher for published time
66+
ensure_publisher_exists(gid_key, publisher->get_topic_name());
67+
68+
const auto & pub_published_time_ = publishers_[gid_key];
69+
70+
// Check if there are any subscribers, otherwise don't do anything
71+
if (pub_published_time_->get_subscription_count() > 0) {
72+
PublishedTime published_time;
73+
74+
published_time.header = header;
75+
published_time.published_stamp = rclcpp::Clock().now();
76+
77+
pub_published_time_->publish(published_time);
78+
}
79+
}
80+
81+
private:
82+
rclcpp::Node * node_;
83+
std::string publisher_topic_suffix_;
84+
rclcpp::QoS qos_;
85+
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+
97+
// ensure that the publisher exists in publisher_ map, if not, create a new one
98+
void ensure_publisher_exists(const rmw_gid_t & gid_key, const std::string & topic_name)
99+
{
100+
if (publishers_.find(gid_key) == publishers_.end()) {
101+
publishers_[gid_key] =
102+
node_->create_publisher<PublishedTime>(topic_name + publisher_topic_suffix_, qos_);
103+
}
104+
}
105+
106+
// store them for each different publisher of the node
107+
std::map<rmw_gid_t, rclcpp::Publisher<PublishedTime>::SharedPtr, GidCompare> publishers_;
108+
};
109+
} // namespace tier4_autoware_utils
110+
111+
#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)