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

feat(goal_planner): improve stopping behavior #10021

Draft
wants to merge 1 commit into
base: main
Choose a base branch
from
Draft
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 1823 to 1844, 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.
//
// 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 @@ -38,6 +38,7 @@
#include <algorithm>
#include <cstddef>
#include <deque>
#include <execution>
#include <functional>
#include <limits>
#include <map>
Expand Down Expand Up @@ -935,7 +936,7 @@

// Sort pull_over_path_candidates based on the order in goal_candidates
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
Expand Down Expand Up @@ -987,7 +988,7 @@

// sorts in descending order so the item with larger margin comes first
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
Expand Down Expand Up @@ -1022,7 +1023,7 @@

// NOTE: this is just partition sort based on curvature threshold within each sub partitions
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
Expand All @@ -1043,7 +1044,7 @@
// the collision check margin and curvature priority.
if (parameters.path_priority == "efficient_path") {
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
// if any of following conditions are met, sort by path type priority
// - both are soft margin
Expand Down Expand Up @@ -1077,7 +1078,7 @@
*/
if (parameters.path_priority == "efficient_path") {
std::stable_sort(
sorted_path_indices.begin(), sorted_path_indices.end(),
std::execution::par, sorted_path_indices.begin(), sorted_path_indices.end(),
[&](const size_t a_i, const size_t b_i) {
const auto & a = pull_over_path_candidates[a_i];
const auto & b = pull_over_path_candidates[b_i];
Expand Down Expand Up @@ -1199,6 +1200,7 @@
universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

output.reference_path = getPreviousModuleOutput().reference_path;
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;

if (!selected_pull_over_path_with_velocity_opt) {
// situation : not safe against static objects use stop_path
Expand Down Expand Up @@ -1351,7 +1353,22 @@

// if pull over path candidates generation is not finished, use previous module output
if (context_data.lane_parking_response.pull_over_path_candidates.empty()) {
return getPreviousModuleOutput();
// return getPreviousModuleOutput();
BehaviorModuleOutput output{};
// const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(context_data);
// output.modified_goal = pull_over_output.modified_goal;
output.path = generateStopPath(context_data, "no path candidate");
output.reference_path = getPreviousModuleOutput().reference_path;
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;

const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);

DrivableAreaInfo current_drivable_area_info{};
current_drivable_area_info.drivable_lanes = target_drivable_lanes;
output.drivable_area_info = utils::combineDrivableAreaInfo(
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info);
return output;
}

BehaviorModuleOutput output{};
Expand Down Expand Up @@ -1386,7 +1403,22 @@

// if pull over path candidates generation is not finished, use previous module output
if (context_data.lane_parking_response.pull_over_path_candidates.empty()) {
return getPreviousModuleOutput();
// return getPreviousModuleOutput();
BehaviorModuleOutput output{};
// const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(context_data);
// output.modified_goal = pull_over_output.modified_goal;
output.path = generateStopPath(context_data, "no path candidate");
output.reference_path = getPreviousModuleOutput().reference_path;
output.turn_signal_info = getPreviousModuleOutput().turn_signal_info;

const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes(
output.path, generateDrivableLanes(), planner_data_->drivable_area_expansion_parameters);

DrivableAreaInfo current_drivable_area_info{};
current_drivable_area_info.drivable_lanes = target_drivable_lanes;
output.drivable_area_info = utils::combineDrivableAreaInfo(
current_drivable_area_info, getPreviousModuleOutput().drivable_area_info);
return output;

Check warning on line 1421 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::planPullOverAsOutput already has high cyclomatic complexity, and now it increases in Lines of Code from 70 to 80. 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.
}

/**
Expand Down
Loading