Skip to content

Commit 48c5fe5

Browse files
committedMar 15, 2024
Revert "feat: add published_time publisher debug to packages (autowarefoundation#6490)"
This reverts commit 7f36c52.
1 parent 70eb8cf commit 48c5fe5

File tree

57 files changed

+6
-153
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

57 files changed

+6
-153
lines changed
 

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

+2-3
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,7 @@ class PublishedTimePublisher
3737
{
3838
}
3939

40-
void publish_if_subscribed(
41-
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
40+
void publish(const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp)
4241
{
4342
const auto & gid_key = publisher->get_gid();
4443

@@ -58,7 +57,7 @@ class PublishedTimePublisher
5857
}
5958
}
6059

61-
void publish_if_subscribed(
60+
void publish(
6261
const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header)
6362
{
6463
const auto & gid_key = publisher->get_gid();

‎control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,6 @@
2828

2929
#include <Eigen/Core>
3030
#include <Eigen/Geometry>
31-
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
3231

3332
#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp"
3433
#include "autoware_auto_control_msgs/msg/longitudinal_command.hpp"
@@ -122,8 +121,6 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node
122121

123122
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
124123

125-
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
126-
127124
void publishProcessingTime(
128125
const double t_ms, const rclcpp::Publisher<Float64Stamped>::SharedPtr pub);
129126
StopWatch<std::chrono::milliseconds> stop_watch_;

0 commit comments

Comments
 (0)