From 79f9eccb835ab07142754ad8a1a7d66f0ece5ba7 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Tue, 21 Jan 2025 22:02:08 +0900 Subject: [PATCH] feat(autoware_obstacle_stop_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_stop_planner (#9906) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_stop_planner Signed-off-by: vish0012 --- .../autoware_obstacle_stop_planner/package.xml | 2 +- .../src/adaptive_cruise_control.cpp | 2 +- .../src/adaptive_cruise_control.hpp | 7 ++++--- .../src/debug_marker.hpp | 4 ++-- .../autoware_obstacle_stop_planner/src/node.hpp | 16 ++++++++-------- 5 files changed, 16 insertions(+), 15 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index ba6364a2b59ee..25332774366b0 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -21,6 +21,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_internal_debug_msgs autoware_motion_utils autoware_perception_msgs autoware_planning_factor_interface @@ -41,7 +42,6 @@ tf2_eigen tf2_geometry_msgs tf2_ros - tier4_debug_msgs tier4_planning_msgs visualization_msgs diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp index 82a4d5a7ec550..3154ce45972a3 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -181,7 +181,7 @@ AdaptiveCruiseController::AdaptiveCruiseController( param_.rough_velocity_rate = node_->declare_parameter(acc_ns + "rough_velocity_rate"); /* publisher */ - pub_debug_ = node_->create_publisher( + pub_debug_ = node_->create_publisher( "~/adaptive_cruise_control/debug_values", 1); } diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp index ce57f585197ad..f4a11bc4314bd 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp @@ -17,10 +17,10 @@ #include +#include #include #include #include -#include #include #include @@ -58,7 +58,8 @@ class AdaptiveCruiseController const PredictedObject & target_object); private: - rclcpp::Publisher::SharedPtr pub_debug_; + rclcpp::Publisher::SharedPtr + pub_debug_; rclcpp::Node * node_; /* @@ -217,7 +218,7 @@ class AdaptiveCruiseController void registerQueToVelocity(const double vel, const rclcpp::Time & vel_time); /* Debug */ - mutable tier4_debug_msgs::msg::Float32MultiArrayStamped debug_values_; + mutable autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_values_; enum DBGVAL { ESTIMATED_VEL_PCL = 0, ESTIMATED_VEL_OBJ = 1, diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index 72e2b52c287f1..3b8b57e7de4c6 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -17,9 +17,9 @@ #include #include +#include #include #include -#include #include #include @@ -41,7 +41,7 @@ using std_msgs::msg::Header; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; enum class PolygonType : int8_t { Vehicle = 0, Collision, SlowDownRange, SlowDown, Obstacle }; diff --git a/planning/autoware_obstacle_stop_planner/src/node.hpp b/planning/autoware_obstacle_stop_planner/src/node.hpp index fba24061896b6..ea8aed19bdcfd 100644 --- a/planning/autoware_obstacle_stop_planner/src/node.hpp +++ b/planning/autoware_obstacle_stop_planner/src/node.hpp @@ -29,6 +29,10 @@ #include #include +#include +#include +#include +#include #include #include #include @@ -36,10 +40,6 @@ #include #include #include -#include -#include -#include -#include #include #include #include @@ -81,13 +81,13 @@ using autoware::universe_utils::Point2d; using autoware::universe_utils::Polygon2d; using autoware::universe_utils::StopWatch; using autoware::vehicle_info_utils::VehicleInfo; +using autoware_internal_debug_msgs::msg::BoolStamped; +using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped; +using autoware_internal_debug_msgs::msg::Float32Stamped; +using autoware_internal_debug_msgs::msg::Float64Stamped; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using tier4_debug_msgs::msg::BoolStamped; -using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_debug_msgs::msg::Float32Stamped; -using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::ExpandStopRange; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand;