From ebba16e44667310a07aa71795e4c8009e7ebc24a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 5 Nov 2024 20:03:47 +0900 Subject: [PATCH] fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (#9234) Signed-off-by: satoshi-ota --- .../src/scene_crosswalk.cpp | 5 +---- .../src/scene_crosswalk.hpp | 3 --- 2 files changed, 1 insertion(+), 7 deletions(-) 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 a56038d3a89d4..057c9d103aeba 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 @@ -199,8 +199,6 @@ CrosswalkModule::CrosswalkModule( collision_info_pub_ = node.create_publisher("~/debug/collision_info", 1); - - vehicle_stop_checker_ = std::make_unique(&node); } bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) @@ -1389,8 +1387,7 @@ void CrosswalkModule::planStop( bool CrosswalkModule::checkRestartSuppression( const PathWithLaneId & ego_path, const std::optional & stop_factor) const { - const auto is_vehicle_stopped = vehicle_stop_checker_->isVehicleStopped(); - if (!is_vehicle_stopped) { + if (!planner_data_->isVehicleStopped()) { return false; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index cd4b8eb46af6c..0747fc725f444 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -18,7 +18,6 @@ #include "autoware/behavior_velocity_crosswalk_module/util.hpp" #include -#include #include #include #include @@ -466,8 +465,6 @@ class CrosswalkModule : public SceneModuleInterface // Debug mutable DebugData debug_data_; - std::unique_ptr vehicle_stop_checker_{nullptr}; - // Stop watch StopWatch stop_watch_;