Skip to content

feat(goal_planner): check pull over lane crossing validity when triggering candidate generation thread #10784

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

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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 @@ -55,8 +55,8 @@ class PathDecisionStateController
const autoware_perception_msgs::msg::PredictedObjects & dynamic_target_objects,
const std::shared_ptr<const PlannerData> planner_data,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const bool is_current_safe, const GoalPlannerParameters & parameters,
const GoalSearcher & goal_searcher,
const bool is_current_safe, const bool lane_change_status_changed,
const GoalPlannerParameters & parameters, const GoalSearcher & goal_searcher,
std::vector<autoware_utils::Polygon2d> & ego_polygons_expanded);

PathDecisionState get_current_state() const { return current_state_; }
Expand All @@ -75,8 +75,8 @@ class PathDecisionStateController
const PredictedObjects & dynamic_target_objects,
const std::shared_ptr<const PlannerData> planner_data,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const bool is_current_safe, const GoalPlannerParameters & parameters,
const GoalSearcher & goal_searcher,
const bool is_current_safe, const bool lane_change_status_changed,
const GoalPlannerParameters & parameters, const GoalSearcher & goal_searcher,
std::vector<autoware_utils::Polygon2d> & ego_polygons_expanded) const;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -302,6 +302,11 @@ class GoalPlannerModule : public SceneModuleInterface
const bool left_side_parking_;

bool trigger_thread_on_approach_{false};

// signal path generator and state manager to regenerate path candidates and remain NOT_DECIDED
std::optional<bool> prev_lane_change_detected_{};
bool lane_change_status_changed_{false};

// pre-generate lane parking paths in a separate thread
rclcpp::TimerBase::SharedPtr lane_parking_timer_;
rclcpp::CallbackGroup::SharedPtr lane_parking_timer_cb_group_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ struct PullOverPath

std::vector<Pose> debug_poses{};

std::optional<PathWithLaneId> debug_processed_prev_module_path;

private:
PullOverPath(
const PullOverPlannerType & type, const size_t id, const Pose & start_pose,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class LaneParkingRequest
const PlannerData & planner_data, const ModuleStatus & current_status,
const BehaviorModuleOutput & upstream_module_output,
const std::optional<PullOverPath> & pull_over_path, const PathDecisionState & prev_data,
const bool trigger_thread_on_approach);
const bool trigger_thread_on_approach, const bool lane_change_status_changed);

const autoware_utils::LinearRing2d vehicle_footprint_;
const GoalCandidates goal_candidates_;
Expand All @@ -60,6 +60,7 @@ class LaneParkingRequest
const std::optional<PullOverPath> & get_pull_over_path() const { return pull_over_path_; }
const PathDecisionState & get_prev_data() const { return prev_data_; }
bool trigger_thread_on_approach() const { return trigger_thread_on_approach_; }
bool lane_change_status_changed() const { return lane_change_status_changed_; }

private:
std::shared_ptr<PlannerData> planner_data_;
Expand All @@ -68,6 +69,7 @@ class LaneParkingRequest
std::optional<PullOverPath> pull_over_path_; //<! pull over path selected by main thread
PathDecisionState prev_data_;
bool trigger_thread_on_approach_{false};
bool lane_change_status_changed_{false};
};

struct LaneParkingResponse
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,23 @@ bool hasDeviatedFromPath(
*/
bool has_stopline_except_terminal(const PathWithLaneId & path);

/**
* @brief find the lanelet that has changed "laterally" from previous lanelet on the routing graph
* @return the lanelet that changed "laterally" if the path is lane changing, otherwise nullopt
*/
std::optional<lanelet::ConstLanelet> find_lane_change_completed_lanelet(
const PathWithLaneId & path, const lanelet::LaneletMapConstPtr lanelet_map,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

/**
* @brief generate lanelets with which pull over path is aligned
* @note if lane changing path is detected, this returns lanelets aligned with later part of the
* lane changing path
*/
lanelet::ConstLanelets get_reference_lanelets_for_pullover(
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const double backward_length, const double forward_length);

} // namespace autoware::behavior_path_planner::goal_planner_utils

#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,14 @@
const PredictedObjects & dynamic_target_objects,
const std::shared_ptr<const PlannerData> planner_data,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const bool is_current_safe, const GoalPlannerParameters & parameters,
const GoalSearcher & goal_searcher,
const bool is_current_safe, const bool lane_change_status_changed,
const GoalPlannerParameters & parameters, const GoalSearcher & goal_searcher,
std::vector<autoware_utils::Polygon2d> & ego_polygons_expanded)
{
const auto next_state = get_next_state(
pull_over_path_opt, upstream_module_has_stopline, now, static_target_objects,
dynamic_target_objects, planner_data, occupancy_grid_map, is_current_safe, parameters,
goal_searcher, ego_polygons_expanded);
dynamic_target_objects, planner_data, occupancy_grid_map, is_current_safe,
lane_change_status_changed, parameters, goal_searcher, ego_polygons_expanded);
current_state_ = next_state;
}

Expand All @@ -48,32 +48,39 @@
const PredictedObjects & dynamic_target_objects,
const std::shared_ptr<const PlannerData> planner_data,
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
const bool is_current_safe, const GoalPlannerParameters & parameters,
const GoalSearcher & goal_searcher,
const bool is_current_safe, const bool lane_change_status_changed,
const GoalPlannerParameters & parameters, const GoalSearcher & goal_searcher,
std::vector<autoware_utils::Polygon2d> & ego_polygons_expanded) const
{
auto next_state = current_state_;

// update safety
if (is_current_safe) {
if (!next_state.safe_start_time) {
next_state.safe_start_time = now;
next_state.is_stable_safe = false;
} else {
next_state.is_stable_safe =
((now - next_state.safe_start_time.value()).seconds() >
parameters.safety_check_params.keep_unsafe_time);
}
} else {
next_state.safe_start_time = std::nullopt;
next_state.is_stable_safe = false;
}

// Once this function returns true, it will continue to return true thereafter
if (next_state.state == PathDecisionState::DecisionKind::DECIDED) {
return next_state;
}

// if lane change is triggered, reference path for pull over must be reset accordingly
if (lane_change_status_changed) {
RCLCPP_INFO(logger_, "[DecidingPathStatus]: NOT_DECIDED. lane change detected");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
return next_state;

Check warning on line 81 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp#L80-L81

Added lines #L80 - L81 were not covered by tests
}

Check warning on line 83 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PathDecisionStateController::get_next_state increases in cyclomatic complexity from 13 to 14, 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.
// while upstream module path has stopline, goal_planner remains NOT_DECIDED
if (upstream_module_has_stopline) {
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,7 @@
const auto & prev_data = local_request.get_prev_data();
const auto trigger_thread_on_approach = local_request.trigger_thread_on_approach();
const auto use_bus_stop_area = local_request.use_bus_stop_area_;
const auto lane_change_status_changed = local_request.lane_change_status_changed();

Check warning on line 272 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#L272

Added line #L272 was not covered by tests

if (!trigger_thread_on_approach) {
return;
Expand Down Expand Up @@ -317,6 +318,10 @@
RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path");
return true;
}
if (lane_change_status_changed) {
RCLCPP_INFO(getLogger(), "[LaneParkingPlanner]: lane_change_status changed, so replan");
return true;

Check warning on line 323 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#L323

Added line #L323 was not covered by tests
}

Check warning on line 324 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

LaneParkingPlanner::onTimer increases in cyclomatic complexity from 18 to 19, 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.
const bool upstream_module_has_stopline_except_terminal =
goal_planner_utils::has_stopline_except_terminal(upstream_module_output.path);
if (upstream_module_has_stopline_except_terminal) {
Expand Down Expand Up @@ -622,7 +627,8 @@
// count is affected
lane_parking_request_.value().update(
*planner_data_, getCurrentStatus(), getPreviousModuleOutput(), pull_over_path,
path_decision_controller_.get_current_state(), trigger_thread_on_approach_);
path_decision_controller_.get_current_state(), trigger_thread_on_approach_,

Check warning on line 630 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#L630

Added line #L630 was not covered by tests
lane_change_status_changed_);
// NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as
// value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since
// behavior_path_planner::run() updates
Expand Down Expand Up @@ -685,6 +691,15 @@
goal_candidates_ = generateGoalCandidates(goal_searcher_.value(), use_bus_stop_area_);
}

const auto lane_change_detected =
goal_planner_utils::find_lane_change_completed_lanelet(
getPreviousModuleOutput().path, planner_data_->route_handler->getLaneletMapPtr(),
planner_data_->route_handler->getRoutingGraphPtr())
.has_value();
lane_change_status_changed_ =
prev_lane_change_detected_ && prev_lane_change_detected_.value() != lane_change_detected;
prev_lane_change_detected_ = lane_change_detected;

Check warning on line 701 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#L701

Added line #L701 was not covered by tests

const lanelet::ConstLanelets current_lanes =
utils::getCurrentLanesFromPath(getPreviousModuleOutput().reference_path, planner_data_);

Expand All @@ -707,6 +722,10 @@
}

if (getCurrentStatus() == ModuleStatus::IDLE) {
if (lane_change_status_changed_) {
[[maybe_unused]] const auto send_only_request = syncWithThreads();
RCLCPP_INFO(getLogger(), "restart preparing goal candidates since lane_change is detected");
}

Check warning on line 728 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#L728

Added line #L728 was not covered by tests
return;
}

Expand Down Expand Up @@ -740,7 +759,8 @@
path_decision_controller_.transit_state(
pull_over_path_recv, upstream_module_has_stopline_except_terminal, clock_->now(),
static_target_objects, dynamic_target_objects, planner_data_, occupancy_grid_map_,
is_current_safe, parameters_, goal_searcher, debug_data_.ego_polygons_expanded);
is_current_safe, lane_change_status_changed_, parameters_, goal_searcher,
debug_data_.ego_polygons_expanded);

Check warning on line 763 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::updateData increases in cyclomatic complexity from 20 to 22, 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.

Check warning on line 763 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#L762-L763

Added lines #L762 - L763 were not covered by tests
const auto new_decision_state = path_decision_controller_.get_current_state();

auto [lane_parking_response, freespace_parking_response] = syncWithThreads();
Expand Down Expand Up @@ -2561,6 +2581,11 @@
createPathMarkerArray(pull_over_path.full_path(), "full_path", 0, 0.0, 0.5, 0.9));
add_debug_marker(
createPathMarkerArray(pull_over_path.getCurrentPath(), "current_path", 0, 0.9, 0.5, 0.0));
if (pull_over_path.debug_processed_prev_module_path) {
add_debug_marker(createPathMarkerArray(
pull_over_path.debug_processed_prev_module_path.value(), "processed_prev_module_path", 0,

Check warning on line 2586 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#L2586

Added line #L2586 was not covered by tests
0.9, 0.5, 0.9));
}

Check warning on line 2588 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::setDebugData increases in cyclomatic complexity from 20 to 21, 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.

// visualize each partial path
for (size_t i = 0; i < pull_over_path.partial_paths().size(); ++i) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,8 @@
[[maybe_unused]] const double jerk_resolution =
std::abs(max_jerk - min_jerk) / shift_sampling_num;

const auto road_lanes = utils::getExtendedCurrentLanesFromPath(
upstream_module_output.path, planner_data, backward_search_length, forward_search_length,
/*forward_only_in_route*/ false);
const auto road_lanes = goal_planner_utils::get_reference_lanelets_for_pullover(
upstream_module_output.path, planner_data, backward_search_length, forward_search_length);

Check warning on line 60 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/bezier_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/bezier_pull_over.cpp#L60

Added line #L60 was not covered by tests

const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, backward_search_length, forward_search_length);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,9 @@

const auto & goal_pose = modified_goal_pose.goal_pose;
// prepare road nad shoulder lanes
const auto road_lanes = utils::getExtendedCurrentLanes(
planner_data, parameters_.backward_goal_search_length, parameters_.forward_goal_search_length,
/*forward_only_in_route*/ false);
const auto road_lanes = goal_planner_utils::get_reference_lanelets_for_pullover(
upstream_module_output.path, planner_data, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);

Check warning on line 56 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#L55-L56

Added lines #L55 - L56 were not covered by tests
const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, parameters_.backward_goal_search_length,
parameters_.forward_goal_search_length);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,8 @@
const int shift_sampling_num = parameters_.shift_sampling_num;
const double jerk_resolution = std::abs(max_jerk - min_jerk) / shift_sampling_num;

const auto road_lanes = utils::getExtendedCurrentLanesFromPath(
upstream_module_output.path, planner_data, backward_search_length, forward_search_length,
/*forward_only_in_route*/ false);
const auto road_lanes = goal_planner_utils::get_reference_lanelets_for_pullover(
upstream_module_output.path, planner_data, backward_search_length, forward_search_length);

Check warning on line 58 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#L58

Added line #L58 was not covered by tests

const auto pull_over_lanes = goal_planner_utils::getPullOverLanes(
*route_handler, left_side_parking_, backward_search_length, forward_search_length);
Expand Down Expand Up @@ -286,6 +285,7 @@
return {};
}

pull_over_path.debug_processed_prev_module_path = processed_prev_module_path;

Check warning on line 288 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

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

ShiftPullOver::generatePullOverPath already has high cyclomatic complexity, and now it increases in Lines of Code from 140 to 141. 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.
return pull_over_path;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
const PlannerData & planner_data, const ModuleStatus & current_status,
const BehaviorModuleOutput & upstream_module_output,
const std::optional<PullOverPath> & pull_over_path, const PathDecisionState & prev_data,
const bool trigger_thread_on_approach)
const bool trigger_thread_on_approach, const bool lane_change_status_changed)
{
planner_data_ = std::make_shared<PlannerData>(planner_data);
planner_data_->route_handler = std::make_shared<RouteHandler>(*(planner_data.route_handler));
Expand All @@ -32,6 +32,7 @@
pull_over_path_ = pull_over_path;
prev_data_ = prev_data;
trigger_thread_on_approach_ = trigger_thread_on_approach;
lane_change_status_changed_ = lane_change_status_changed;

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

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/thread_data.cpp#L35

Added line #L35 was not covered by tests
}

void FreespaceParkingRequest::initializeOccupancyGridMap(
Expand Down
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/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Primitive Obsession

The ratio of primitive types in function arguments decreases from 30.77% to 30.66%, threshold = 30.0%. The functions in this file have too many primitive types (e.g. int, double, float) in their function argument lists. Using many primitive types lead to the code smell Primitive Obsession. Avoid adding more primitive arguments.
//
// 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 @@ -1076,4 +1076,51 @@
path.points.size();
}

std::optional<lanelet::ConstLanelet> find_lane_change_completed_lanelet(

Check warning on line 1079 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L1079

Added line #L1079 was not covered by tests
const PathWithLaneId & path, const lanelet::LaneletMapConstPtr lanelet_map,
const lanelet::routing::RoutingGraphConstPtr routing_graph)
{
std::vector<lanelet::Id> path_lane_ids;
for (const auto & point : path.points) {
const auto & lane_ids = point.lane_ids;
for (const auto & lane_id : lane_ids) {
if (std::find(path_lane_ids.begin(), path_lane_ids.end(), lane_id) == path_lane_ids.end()) {
path_lane_ids.push_back(lane_id);
}
}
}

if (path_lane_ids.size() < 2) {
return std::nullopt;

Check warning on line 1094 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L1094

Added line #L1094 was not covered by tests
}
for (unsigned i = 0, j = 1; i < path_lane_ids.size() && j < path_lane_ids.size(); i++, j++) {
const auto & lane1 = lanelet_map->laneletLayer.get(path_lane_ids.at(i));
const auto & lane2 = lanelet_map->laneletLayer.get(path_lane_ids.at(j));
const auto & followings = routing_graph->following(lane1);
if (std::any_of(followings.begin(), followings.end(), [&](const auto & lane) {
return lane.id() == lane2.id();
})) {
continue;
}
return lane2;
}
return std::nullopt;

Check warning on line 1107 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L1106-L1107

Added lines #L1106 - L1107 were not covered by tests
}

Check warning on line 1108 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

find_lane_change_completed_lanelet has a cyclomatic complexity of 9, 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.

lanelet::ConstLanelets get_reference_lanelets_for_pullover(

Check warning on line 1110 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L1110

Added line #L1110 was not covered by tests
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data,
const double backward_length, const double forward_length)
{
const auto & routing_graph = planner_data->route_handler->getRoutingGraphPtr();

Check warning on line 1114 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L1114

Added line #L1114 was not covered by tests
const auto & lanelet_map = planner_data->route_handler->getLaneletMapPtr();
const auto lane_change_complete_lane =
find_lane_change_completed_lanelet(path, lanelet_map, routing_graph);
if (!lane_change_complete_lane) {
return utils::getExtendedCurrentLanesFromPath(
path, planner_data, backward_length, forward_length,
/*forward_only_in_route*/ false);
}
return planner_data->route_handler->getLaneletSequence(
*lane_change_complete_lane, backward_length, forward_length);
Comment on lines +1123 to +1124
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this can't get lanes after goal?

}
} // namespace autoware::behavior_path_planner::goal_planner_utils
Loading