diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index 9aa3c7a58346c..8e3903f0e8e3a 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs diagnostic_msgs rclcpp rclcpp_components diff --git a/system/diagnostic_graph_utils/src/node/logging.cpp b/system/diagnostic_graph_utils/src/node/logging.cpp index 2d433720bea27..8053dd405ecdf 100644 --- a/system/diagnostic_graph_utils/src/node/logging.cpp +++ b/system/diagnostic_graph_utils/src/node/logging.cpp @@ -33,7 +33,7 @@ LoggingNode::LoggingNode(const rclcpp::NodeOptions & options) : Node("logging", sub_graph_.register_create_callback(std::bind(&LoggingNode::on_create, this, _1)); sub_graph_.subscribe(*this, 1); - pub_error_graph_text_ = create_publisher( + pub_error_graph_text_ = create_publisher( "~/debug/error_graph_text", rclcpp::QoS(1)); const auto period = rclcpp::Rate(declare_parameter("show_rate")).period(); @@ -67,12 +67,12 @@ void LoggingNode::on_timer() RCLCPP_WARN_STREAM(get_logger(), prefix_message << std::endl << dump_text_.str()); } - tier4_debug_msgs::msg::StringStamped message; + autoware_internal_debug_msgs::msg::StringStamped message; message.stamp = now(); message.data = dump_text_.str(); pub_error_graph_text_->publish(message); } else { - tier4_debug_msgs::msg::StringStamped message; + autoware_internal_debug_msgs::msg::StringStamped message; message.stamp = now(); pub_error_graph_text_->publish(message); } diff --git a/system/diagnostic_graph_utils/src/node/logging.hpp b/system/diagnostic_graph_utils/src/node/logging.hpp index 17d33499a1513..81acfcd2ad82f 100644 --- a/system/diagnostic_graph_utils/src/node/logging.hpp +++ b/system/diagnostic_graph_utils/src/node/logging.hpp @@ -19,7 +19,7 @@ #include -#include "tier4_debug_msgs/msg/string_stamped.hpp" +#include "autoware_internal_debug_msgs/msg/string_stamped.hpp" #include #include @@ -37,7 +37,8 @@ class LoggingNode : public rclcpp::Node void on_timer(); void dump_unit(DiagUnit * unit, int depth, const std::string & indent); DiagGraphSubscription sub_graph_; - rclcpp::Publisher::SharedPtr pub_error_graph_text_; + rclcpp::Publisher::SharedPtr + pub_error_graph_text_; rclcpp::TimerBase::SharedPtr timer_; DiagUnit * root_unit_;