Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(start_planner, goal_planner): refactor lane departure checker initialization #9944

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,12 @@
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;

Check warning on line 35 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp#L32-L35

Added lines #L32 - L35 were not covered by tests
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 @@
{
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;

Check warning on line 38 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp#L35-L38

Added lines #L35 - L38 were not covered by tests
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
Loading