diff --git a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp
index cf545d1a967e7..7f343c5a2a60f 100644
--- a/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp
+++ b/planning/autoware_path_optimizer/include/autoware/path_optimizer/type_alias.hpp
@@ -15,6 +15,7 @@
#ifndef AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_
#define AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_
+#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/string_stamped.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/path_point.hpp"
@@ -25,7 +26,6 @@
#include "geometry_msgs/msg/twist.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "std_msgs/msg/header.hpp"
-#include "tier4_debug_msgs/msg/float64_stamped.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
namespace autoware::path_optimizer
@@ -43,8 +43,8 @@ using nav_msgs::msg::Odometry;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
// debug
+using autoware_internal_debug_msgs::msg::Float64Stamped;
using autoware_internal_debug_msgs::msg::StringStamped;
-using tier4_debug_msgs::msg::Float64Stamped;
} // namespace autoware::path_optimizer
#endif // AUTOWARE__PATH_OPTIMIZER__TYPE_ALIAS_HPP_
diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml
index 21ce487af6f4c..26e242c94902f 100644
--- a/planning/autoware_path_optimizer/package.xml
+++ b/planning/autoware_path_optimizer/package.xml
@@ -28,7 +28,6 @@
rclcpp_components
std_msgs
tf2_ros
- tier4_debug_msgs
tier4_planning_msgs
visualization_msgs
diff --git a/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py b/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py
index 29dfccb533fbe..604aa1afeed18 100755
--- a/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py
+++ b/planning/autoware_path_optimizer/scripts/calculation_time_plotter.py
@@ -17,10 +17,10 @@
import argparse
from collections import deque
+from autoware_internal_debug_msgs.msg import StringStamped
import matplotlib.pyplot as plt
import rclpy
from rclpy.node import Node
-from tier4_debug_msgs.msg import StringStamped
class CalculationCostAnalyzer(Node):