Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jan 17, 2024
1 parent 7450b19 commit 3444108
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ class ShiftPullOut : public PullOutPlannerBase
public:
explicit ShiftPullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
std::shared_ptr<LaneDepartureChecker> & lane_departure_checker, const lanelet::ConstLanelets & expanded_drivable_lanes);
std::shared_ptr<LaneDepartureChecker> & lane_departure_checker,
const lanelet::ConstLanelets & expanded_drivable_lanes);

PlannerType getPlannerType() override { return PlannerType::SHIFT; };
std::optional<PullOutPath> plan(const Pose & start_pose, const Pose & goal_pose) override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,11 @@ using start_planner_utils::getPullOutLanes;

ShiftPullOut::ShiftPullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
std::shared_ptr<LaneDepartureChecker> & lane_departure_checker, const lanelet::ConstLanelets & expanded_drivable_lanes)
: PullOutPlannerBase{node, parameters}, lane_departure_checker_{lane_departure_checker}, expanded_drivable_lanes_{expanded_drivable_lanes}
std::shared_ptr<LaneDepartureChecker> & lane_departure_checker,
const lanelet::ConstLanelets & expanded_drivable_lanes)
: PullOutPlannerBase{node, parameters},
lane_departure_checker_{lane_departure_checker},
expanded_drivable_lanes_{expanded_drivable_lanes}
{
}

Expand All @@ -53,7 +56,6 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
/*forward_only_in_route*/ true);


// find candidate paths
auto pull_out_paths = calcPullOutPaths(*route_handler, road_lanes, start_pose, goal_pose);
if (pull_out_paths.empty()) {
Expand All @@ -77,8 +79,6 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
shift_path.points.begin() + pull_out_end_idx + 1);
}



// crop backward path
// removes points which are out of lanes up to the start pose.
// this ensures that the backward_path stays within the drivable area when starting from a
Expand Down Expand Up @@ -106,7 +106,8 @@ std::optional<PullOutPath> ShiftPullOut::plan(const Pose & start_pose, const Pos
// check lane departure
if (
parameters_.check_shift_path_lane_departure &&
lane_departure_checker_->checkPathWillLeaveLane(expanded_drivable_lanes_, path_shift_start_to_end)) {
lane_departure_checker_->checkPathWillLeaveLane(
expanded_drivable_lanes_, path_shift_start_to_end)) {
continue;
}

Expand Down

0 comments on commit 3444108

Please sign in to comment.