diff --git a/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp b/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp index afa0ae61..423b05f1 100644 --- a/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp +++ b/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp @@ -22,9 +22,9 @@ #include #include +#include #include #include -#include class LateralErrorPublisher : public rclcpp::Node { diff --git a/common/tier4_debug_tools/package.xml b/common/tier4_debug_tools/package.xml index 509660ae..978bf4dd 100644 --- a/common/tier4_debug_tools/package.xml +++ b/common/tier4_debug_tools/package.xml @@ -10,6 +10,7 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs autoware_motion_utils autoware_planning_msgs autoware_universe_utils @@ -17,7 +18,6 @@ rclcpp rclcpp_components tf2_ros - autoware_internal_debug_msgs launch_ros python3-rtree diff --git a/common/tier4_debug_tools/src/lateral_error_publisher.cpp b/common/tier4_debug_tools/src/lateral_error_publisher.cpp index 60c67adf..d6030e9c 100644 --- a/common/tier4_debug_tools/src/lateral_error_publisher.cpp +++ b/common/tier4_debug_tools/src/lateral_error_publisher.cpp @@ -35,10 +35,11 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op sub_ground_truth_pose_ = create_subscription( "~/input/ground_truth_pose_with_covariance", rclcpp::QoS{1}, std::bind(&LateralErrorPublisher::onGroundTruthPose, this, _1)); - pub_control_lateral_error_ = - create_publisher("~/control_lateral_error", 1); + pub_control_lateral_error_ = create_publisher( + "~/control_lateral_error", 1); pub_localization_lateral_error_ = - create_publisher("~/localization_lateral_error", 1); + create_publisher( + "~/localization_lateral_error", 1); pub_lateral_error_ = create_publisher("~/lateral_error", 1); }