Skip to content

Commit

Permalink
refactor(autoware_autonomous_emergency_braking): rename info_marker_p…
Browse files Browse the repository at this point in the history
…ublisher to virtual_wall_publisher (autowarefoundation#9078)

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara authored Oct 11, 2024
1 parent f5818f7 commit 543b45e
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -341,7 +341,7 @@ class AEB : public rclcpp::Node
// publisher
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;
rclcpp::Publisher<MarkerArray>::SharedPtr debug_marker_publisher_;
rclcpp::Publisher<MarkerArray>::SharedPtr info_marker_publisher_;
rclcpp::Publisher<MarkerArray>::SharedPtr virtual_wall_publisher_;
rclcpp::Publisher<autoware::universe_utils::ProcessingTimeDetail>::SharedPtr
debug_processing_time_detail_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr debug_rss_distance_publisher_;
Expand Down
8 changes: 4 additions & 4 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
pub_obstacle_pointcloud_ =
this->create_publisher<sensor_msgs::msg::PointCloud2>("~/debug/obstacle_pointcloud", 1);
debug_marker_publisher_ = this->create_publisher<MarkerArray>("~/debug/markers", 1);
info_marker_publisher_ = this->create_publisher<MarkerArray>("~/info/markers", 1);
virtual_wall_publisher_ = this->create_publisher<MarkerArray>("~/virtual_wall", 1);
debug_rss_distance_publisher_ =
this->create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/debug/rss_distance", 1);
}
Expand Down Expand Up @@ -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()) {
Expand All @@ -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;
Expand All @@ -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)
Expand Down

0 comments on commit 543b45e

Please sign in to comment.