From 225121a926eebe6bb1e2fe46c124aaa11d50f06b Mon Sep 17 00:00:00 2001 From: yuki-takagi-66 Date: Fri, 17 Jan 2025 16:18:57 +0900 Subject: [PATCH] po Signed-off-by: yuki-takagi-66 --- .../autoware/behavior_velocity_crosswalk_module/util.hpp | 1 + .../src/debug.cpp | 7 +++++++ .../src/scene_crosswalk.cpp | 5 +++-- 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp index 64c98017d3007..137f21adadafa 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/include/autoware/behavior_velocity_crosswalk_module/util.hpp @@ -78,6 +78,7 @@ struct DebugData std::vector stop_poses; std::vector slow_poses; + std::vector pass_poses; std::vector stop_factor_points; std::vector crosswalk_polygon; std::vector> ego_polygons; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp index 757803ef35578..0ec5a2a944059 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/debug.cpp @@ -213,6 +213,13 @@ autoware::motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls() wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); virtual_walls.push_back(wall); } + wall.style = autoware::motion_utils::VirtualWallType::pass; + wall.text += debug_data_.virtual_wall_suffix; + for (const auto & p : debug_data_.pass_poses) { + wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0); + virtual_walls.push_back(wall); + } + return virtual_walls; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 844647e33f8c0..2cca72e919722 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -476,12 +476,13 @@ std::optional CrosswalkModule::calcStopPose( return strong_brk_dist_opt ? strong_brk_dist_opt.value() : 0.0; }(); if (selected_stop.dist < strong_brk_dist - p.overrun_threshold_length_for_no_stop_decision) { - RCLCPP_INFO( - logger_, + RCLCPP_INFO_THROTTLE( + logger_, *clock_, 1000, "Abandon to stop. " "Can not stop against the nearest pedestrian with a specified deceleration. " "dist to stop: %f, braking distance: %f", selected_stop.dist, strong_brk_dist); + debug_data_.pass_poses.push_back(selected_stop.pose); return std::nullopt; }