From d178e04526096ced04059392826e79da257f18b5 Mon Sep 17 00:00:00 2001 From: vish0012 Date: Thu, 26 Dec 2024 11:44:11 +0900 Subject: [PATCH] feat : replace tier4_debug_msgs to autoware_internal_debug_msgs --- .../autoware_autonomous_emergency_braking/src/node.cpp | 4 ++-- .../autoware/control_validator/control_validator.hpp | 4 ++-- .../lane_departure_checker_node.cpp | 10 +++++----- control/autoware_mpc_lateral_controller/package.xml | 2 +- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index eb0884e4f344e..0d2c6d78748d9 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -155,7 +155,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) debug_marker_publisher_ = this->create_publisher("~/debug/markers", 1); virtual_wall_publisher_ = this->create_publisher("~/virtual_wall", 1); debug_rss_distance_publisher_ = - this->create_publisher("~/debug/rss_distance", 1); + this->create_publisher("~/debug/rss_distance", 1); metrics_pub_ = this->create_publisher("~/metrics", 1); } // Diagnostics @@ -647,7 +647,7 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object return ego_stopping_distance + obj_braking_distance + longitudinal_offset_margin_; }); - tier4_debug_msgs::msg::Float32Stamped rss_distance_msg; + autoware_internal_debug_msgs::msg::Float32Stamped rss_distance_msg; rss_distance_msg.stamp = get_clock()->now(); rss_distance_msg.data = rss_dist; debug_rss_distance_publisher_->publish(rss_distance_msg); diff --git a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp index 080e8f0e6abc3..f78ccd65d6cb8 100644 --- a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp +++ b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include @@ -139,7 +139,7 @@ class ControlValidator : public rclcpp::Node universe_utils::InterProcessPollingSubscriber::SharedPtr sub_reference_traj_; rclcpp::Publisher::SharedPtr pub_status_; rclcpp::Publisher::SharedPtr pub_markers_; - rclcpp::Publisher::SharedPtr pub_processing_time_; + rclcpp::Publisher::SharedPtr pub_processing_time_; // system parameters int64_t diag_error_count_threshold_ = 0; diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 366b84a1f6131..c7c21f03c12c1 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -171,7 +171,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o // Publisher processing_time_publisher_ = - this->create_publisher("~/debug/processing_time_ms", 1); + this->create_publisher("~/debug/processing_time_ms", 1); // Nothing // Diagnostic Updater @@ -342,10 +342,10 @@ void LaneDepartureCheckerNode::onTimer() { const auto & deviation = output_.trajectory_deviation; - debug_publisher_.publish( + debug_publisher_.publish( "deviation/lateral", deviation.lateral); - debug_publisher_.publish("deviation/yaw", deviation.yaw); - debug_publisher_.publish( + debug_publisher_.publish("deviation/yaw", deviation.yaw); + debug_publisher_.publish( "deviation/yaw_deg", rad2deg(deviation.yaw)); } processing_time_map["Node: publishTrajectoryDeviation"] = stop_watch.toc(true); @@ -361,7 +361,7 @@ void LaneDepartureCheckerNode::onTimer() processing_time_map["Total"] = stop_watch.toc("Total"); processing_diag_publisher_.publish(processing_time_map); - tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + autoware_internal_debug_msgs::msg::Float64Stamped processing_time_msg; processing_time_msg.stamp = get_clock()->now(); processing_time_msg.data = processing_time_map["Total"]; processing_time_publisher_->publish(processing_time_msg); diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index b450af05ea0e1..648396e10fb38 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -36,7 +36,7 @@ std_msgs tf2 tf2_ros - tier4_debug_msgs + autoware_internal_debug_msgs ament_cmake_ros ament_lint_auto