diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index b43a7d0d0369a..7aeedd096862d 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -59,18 +59,18 @@ typedef boost::geometry::index::rtree efficient_path_order{}; + double lane_departure_check_expansion_margin{0.0}; // shift path bool enable_shift_parking{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index ae41eb7a45ccf..7792b427c5fa1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -68,6 +68,10 @@ GoalPlannerModule::GoalPlannerModule( { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); + lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + parameters->lane_departure_check_expansion_margin; + lane_departure_checker.setParam(lane_departure_checker_params); occupancy_grid_map_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp index b86bbbca7d98b..2d565607ec610 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp @@ -137,6 +137,8 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node) p.path_priority = node->declare_parameter(ns + "path_priority"); p.efficient_path_order = node->declare_parameter>(ns + "efficient_path_order"); + p.lane_departure_check_expansion_margin = + node->declare_parameter(ns + "lane_departure_check_expansion_margin"); } // shift parking @@ -526,6 +528,9 @@ void GoalPlannerModuleManager::updateModuleParams( updateParam(parameters, ns + "deceleration_interval", p->deceleration_interval); updateParam( parameters, ns + "after_shift_straight_distance", p->after_shift_straight_distance); + updateParam( + parameters, ns + "lane_departure_check_expansion_margin", + p->lane_departure_check_expansion_margin); } // parallel parking common