diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp index 949a8de361409..8ba05be36ae56 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp @@ -51,8 +51,6 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".stop_position.stop_distance_from_object_preferred"); cp.stop_distance_from_object_limit = getOrDeclareParameter(node, ns + ".stop_position.stop_distance_from_object_limit"); - cp.far_object_threshold = - getOrDeclareParameter(node, ns + ".stop_position.far_object_threshold"); cp.stop_position_threshold = getOrDeclareParameter(node, ns + ".stop_position.stop_position_threshold"); cp.min_acc_preferred = 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 057c9d103aeba..51a0b4aa23fde 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 @@ -420,9 +420,7 @@ std::optional CrosswalkModule::calcStopPose( if (!ped_stop_pref_opt.has_value()) { RCLCPP_INFO(logger_, "Failure to calculate pref_stop."); return std::nullopt; - } else if ( - default_stop_opt.has_value() && ped_stop_pref_opt->dist > default_stop_opt->dist && - ped_stop_pref_opt->dist < default_stop_opt->dist + planner_param_.far_object_threshold) { + } else if (default_stop_opt.has_value() && ped_stop_pref_opt->dist > default_stop_opt->dist) { return default_stop_opt; } else { return ped_stop_pref_opt; 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 80f348027e1fd..de696aa670ad3 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 @@ -122,7 +122,6 @@ class CrosswalkModule : public SceneModuleInterface double stop_distance_from_object_preferred; double stop_distance_from_object_limit; double stop_distance_from_crosswalk; - double far_object_threshold; double stop_position_threshold; double min_acc_preferred; double min_jerk_preferred;