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(goal_planner): fix waiting approval path of backward parking #10015

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1866 to 1872, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 6.52 to 6.56, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -1650,12 +1650,20 @@
return PathWithLaneId{};
}

// extend previous module path to generate reference path for stop path
// Generate reference_path to extend the previous path.
// If pull_over_path is ARC_BACKWARD, generate path to the start_pose of the pull_over_path,
// otherwise, generate path to the goal_pose.
const auto & pull_over_path_opt = context_data.pull_over_path_opt;

Check warning on line 1656 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1656

Added line #L1656 was not covered by tests
const auto reference_path = std::invoke([&]() -> PathWithLaneId {
const auto s_current = lanelet::utils::getArcCoordinates(current_lanes, current_pose).length;
const double s_start = std::max(0.0, s_current - common_parameters.backward_path_length);
const bool is_arc_backward =
pull_over_path_opt.has_value() &&
pull_over_path_opt.value().type() == PullOverPlannerType::ARC_BACKWARD;
const Pose path_end_pose =
is_arc_backward ? pull_over_path_opt.value().start_pose() : route_handler->getGoalPose();

Check warning on line 1664 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1664

Added line #L1664 was not covered by tests
const double s_end = std::clamp(
lanelet::utils::getArcCoordinates(current_lanes, route_handler->getGoalPose()).length,
lanelet::utils::getArcCoordinates(current_lanes, path_end_pose).length,

Check warning on line 1666 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L1666

Added line #L1666 was not covered by tests
s_current + std::numeric_limits<double>::epsilon(),
s_current + common_parameters.forward_path_length);
return route_handler->getCenterLinePath(current_lanes, s_start, s_end, true);
Expand Down Expand Up @@ -1685,8 +1693,8 @@
// difference between the outer and inner sides)
// 4. feasible stop
const auto stop_pose_opt = std::invoke([&]() -> std::optional<Pose> {
if (context_data.pull_over_path_opt)
return std::make_optional<Pose>(context_data.pull_over_path_opt.value().start_pose());
if (pull_over_path_opt)
return std::make_optional<Pose>(pull_over_path_opt.value().start_pose());

Check warning on line 1697 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

GoalPlannerModule::generateStopPath increases in cyclomatic complexity from 13 to 15, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
if (context_data.lane_parking_response.closest_start_pose)
return context_data.lane_parking_response.closest_start_pose;
return decel_pose;
Expand Down
Loading