Skip to content

Commit

Permalink
fix(start_planner, goal_planner): refactor lane departure checker ini…
Browse files Browse the repository at this point in the history
…tialization (#9944)
  • Loading branch information
kyoichi-sugahara authored Jan 16, 2025
1 parent dd632fc commit 62e07a1
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,12 @@ GeometricPullOver::GeometricPullOver(
rclcpp::Node & node, const GoalPlannerParameters & parameters, const bool is_forward)
: PullOverPlannerBase{node, parameters},
parallel_parking_parameters_{parameters.parallel_parking_parameters},
lane_departure_checker_{
lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_},
lane_departure_checker_{[&]() {
auto lane_departure_checker_params = lane_departure_checker::Param{};
lane_departure_checker_params.footprint_extra_margin =
parameters.lane_departure_check_expansion_margin;
return LaneDepartureChecker{lane_departure_checker_params, vehicle_info_};
}()},
is_forward_{is_forward},
left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE}
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,12 @@ namespace autoware::behavior_path_planner
{
ShiftPullOver::ShiftPullOver(rclcpp::Node & node, const GoalPlannerParameters & parameters)
: PullOverPlannerBase{node, parameters},
lane_departure_checker_{
lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin}, vehicle_info_},
lane_departure_checker_{[&]() {
auto lane_departure_checker_params = lane_departure_checker::Param{};
lane_departure_checker_params.footprint_extra_margin =
parameters.lane_departure_check_expansion_margin;
return LaneDepartureChecker{lane_departure_checker_params, vehicle_info_};
}()},
left_side_parking_{parameters.parking_policy == ParkingPolicy::LEFT_SIDE}
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,12 @@ GeometricPullOut::GeometricPullOut(
: PullOutPlannerBase{node, parameters, time_keeper},
parallel_parking_parameters_{parameters.parallel_parking_parameters}
{
auto lane_departure_checker_params = autoware::lane_departure_checker::Param{};
lane_departure_checker_params.footprint_extra_margin =
parameters.lane_departure_check_expansion_margin;
lane_departure_checker_ =
std::make_shared<autoware::lane_departure_checker::LaneDepartureChecker>(
autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin},
vehicle_info_, time_keeper_);
lane_departure_checker_params, vehicle_info_);
planner_.setParameters(parallel_parking_parameters_);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,10 +44,12 @@ ShiftPullOut::ShiftPullOut(
std::shared_ptr<universe_utils::TimeKeeper> time_keeper)
: PullOutPlannerBase{node, parameters, time_keeper}
{
autoware::lane_departure_checker::Param lane_departure_checker_params;
lane_departure_checker_params.footprint_extra_margin =
parameters.lane_departure_check_expansion_margin;
lane_departure_checker_ =
std::make_shared<autoware::lane_departure_checker::LaneDepartureChecker>(
autoware::lane_departure_checker::Param{parameters.lane_departure_check_expansion_margin},
vehicle_info_, time_keeper_);
lane_departure_checker_params, vehicle_info_, time_keeper_);
}

std::optional<PullOutPath> ShiftPullOut::plan(
Expand Down

0 comments on commit 62e07a1

Please sign in to comment.