From 543b45eea074ffd511863c6cac18916f8e38ccef Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Fri, 11 Oct 2024 16:37:01 +0900 Subject: [PATCH] refactor(autoware_autonomous_emergency_braking): rename info_marker_publisher to virtual_wall_publisher (#9078) Signed-off-by: kyoichi-sugahara --- .../autoware/autonomous_emergency_braking/node.hpp | 2 +- .../autoware_autonomous_emergency_braking/src/node.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index 214a6dc309210..32bedd15c5c53 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -341,7 +341,7 @@ class AEB : public rclcpp::Node // publisher rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_; rclcpp::Publisher::SharedPtr debug_marker_publisher_; - rclcpp::Publisher::SharedPtr info_marker_publisher_; + rclcpp::Publisher::SharedPtr virtual_wall_publisher_; rclcpp::Publisher::SharedPtr debug_processing_time_detail_pub_; rclcpp::Publisher::SharedPtr debug_rss_distance_publisher_; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index b3988ba238fe7..df78ffc156802 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -138,7 +138,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) pub_obstacle_pointcloud_ = this->create_publisher("~/debug/obstacle_pointcloud", 1); debug_marker_publisher_ = this->create_publisher("~/debug/markers", 1); - info_marker_publisher_ = this->create_publisher("~/info/markers", 1); + virtual_wall_publisher_ = this->create_publisher("~/virtual_wall", 1); debug_rss_distance_publisher_ = this->create_publisher("~/debug/rss_distance", 1); } @@ -398,7 +398,7 @@ bool AEB::fetchLatestData() void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) { MarkerArray debug_markers; - MarkerArray info_markers; + MarkerArray virtual_wall_marker; checkCollision(debug_markers); if (!collision_data_keeper_.checkCollisionExpired()) { @@ -414,7 +414,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) addCollisionMarker(data.value(), debug_markers); } } - addVirtualStopWallMarker(info_markers); + addVirtualStopWallMarker(virtual_wall_marker); } else { const std::string error_msg = "[AEB]: No Collision"; const auto diag_level = DiagnosticStatus::OK; @@ -423,7 +423,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) // publish debug markers debug_marker_publisher_->publish(debug_markers); - info_marker_publisher_->publish(info_markers); + virtual_wall_publisher_->publish(virtual_wall_marker); } bool AEB::checkCollision(MarkerArray & debug_markers)