Skip to content

Commit

Permalink
prevent infinite loop
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kyoichi-sugahara committed Jul 8, 2024
1 parent e1cd1da commit 4db069f
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,8 @@ class PlannerManager
* @details in this function, expired modules (ModuleStatus::FAILURE or ModuleStatus::SUCCESS) are
* removed from approved_module_ptrs_.
*/
BehaviorModuleOutput runApprovedModules(const std::shared_ptr<PlannerData> & data);
BehaviorModuleOutput runApprovedModules(
const std::shared_ptr<PlannerData> & data, std::vector<SceneModulePtr> & deleted_modules);

/**
* @brief select a module that should be execute at first.
Expand All @@ -423,7 +424,8 @@ class PlannerManager
* @return request modules.
*/
std::vector<SceneModulePtr> getRequestModules(
const BehaviorModuleOutput & previous_module_output) const;
const BehaviorModuleOutput & previous_module_output,
const std::vector<SceneModulePtr> & deleted_modules) const;

/**
* @brief checks whether a path of trajectory has forward driving direction
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,17 +127,18 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr<PlannerData> & da
"Ego is out of route, no module is running. Skip running scene modules.");
return output;
}
std::vector<SceneModulePtr> deleted_modules; // store the deleted from approved modules

for (size_t itr_num = 1;; ++itr_num) {
/**
* STEP1: get approved modules' output
*/
auto approved_modules_output = runApprovedModules(data);
auto approved_modules_output = runApprovedModules(data, deleted_modules);

/**
* STEP2: check modules that need to be launched
*/
const auto request_modules = getRequestModules(approved_modules_output);
const auto request_modules = getRequestModules(approved_modules_output, deleted_modules);

Check warning on line 141 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PlannerManager::run already has high cyclomatic complexity, and now it increases in Lines of Code from 74 to 75. 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.

/**
* STEP3: if there is no module that need to be launched, return approved modules' output
Expand Down Expand Up @@ -250,7 +251,8 @@ void PlannerManager::generateCombinedDrivableArea(
}

std::vector<SceneModulePtr> PlannerManager::getRequestModules(
const BehaviorModuleOutput & previous_module_output) const
const BehaviorModuleOutput & previous_module_output,
const std::vector<SceneModulePtr> & deleted_modules) const
{
if (previous_module_output.path.points.empty()) {
RCLCPP_ERROR_STREAM(
Expand All @@ -268,6 +270,18 @@ std::vector<SceneModulePtr> PlannerManager::getRequestModules(

for (const auto & manager_ptr : manager_ptrs_) {
stop_watch_.tic(manager_ptr->name());
/**
* skip the module that is already deleted.
*/
{
const auto name = manager_ptr->name();
const auto find_deleted_module = [&name](const auto & m) { return m->name() == name; };
const auto itr =
std::find_if(deleted_modules.begin(), deleted_modules.end(), find_deleted_module);
if (itr != deleted_modules.end()) {
continue;
}
}

Check warning on line 284 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PlannerManager::getRequestModules increases in cyclomatic complexity from 25 to 27, 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 notice on line 284 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

PlannerManager::getRequestModules increases from 2 to 3 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

/**
* determine the execution capability of modules based on existing approved modules.
Expand Down Expand Up @@ -655,7 +669,8 @@ std::pair<SceneModulePtr, BehaviorModuleOutput> PlannerManager::runRequestModule
return std::make_pair(module_ptr, results.at(module_ptr->name()));
}

BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<PlannerData> & data)
BehaviorModuleOutput PlannerManager::runApprovedModules(
const std::shared_ptr<PlannerData> & data, std::vector<SceneModulePtr> & deleted_modules)
{
std::unordered_map<std::string, BehaviorModuleOutput> results;
BehaviorModuleOutput output = getReferencePath(data);
Expand Down Expand Up @@ -771,6 +786,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
const auto itr = std::find_if(
approved_module_ptrs_.begin(), approved_module_ptrs_.end(),
[](const auto & m) { return m->getCurrentStatus() == ModuleStatus::FAILURE; });
if (itr != approved_module_ptrs_.end()) {
deleted_modules.push_back(*itr);
}

std::for_each(itr, approved_module_ptrs_.end(), [this](auto & m) {
debug_info_.emplace_back(m, Action::DELETE, "From Approved");
Expand Down Expand Up @@ -842,6 +860,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
}))
resetCurrentRouteLanelet(data);

std::copy_if(
itr, approved_module_ptrs_.end(), std::back_inserter(deleted_modules), success_module_cond);

Check warning on line 865 in planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PlannerManager::runApprovedModules increases in cyclomatic complexity from 15 to 16, 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.
std::for_each(itr, approved_module_ptrs_.end(), [&](auto & m) {
debug_info_.emplace_back(m, Action::DELETE, "From Approved");
deleteExpiredModules(m);
Expand Down

0 comments on commit 4db069f

Please sign in to comment.