Skip to content

Commit 36a1d14

Browse files
feat(autoware_behavior_path_planner): prevent infinite loop in approving scene module process (#7881)
* prevent infinite loop Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * calculate max_iteration_num from number of scene modules Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> * add doxygen explanation for calculateMaxIterationNum Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp> --------- Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 0eae67c commit 36a1d14

File tree

4 files changed

+56
-15
lines changed

4 files changed

+56
-15
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner/config/behavior_path_planner.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
/**:
22
ros__parameters:
3-
max_iteration_num: 100
43
traffic_light_signal_timeout: 1.0
54
planning_hz: 10.0
65
backward_path_length: 5.0

planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp

+19-4
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ struct SceneModuleStatus
9797
class PlannerManager
9898
{
9999
public:
100-
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num);
100+
explicit PlannerManager(rclcpp::Node & node);
101101

102102
/**
103103
* @brief run all candidate and approved modules.
@@ -112,6 +112,17 @@ class PlannerManager
112112
*/
113113
void launchScenePlugin(rclcpp::Node & node, const std::string & name);
114114

115+
/**
116+
* @brief calculate max iteration numbers.
117+
* Let N be the number of scene modules. The maximum number of iterations executed in a loop is N,
118+
* but after that, if there are any modules that have succeeded or failed, the approve_modules of
119+
* all modules are cleared, and the loop is executed for N-1 modules. As this process repeats, it
120+
* becomes N + (N-1) + (N-2) + … + 1, therefore the maximum number of iterations is N(N+1)/2.
121+
* @param number of scene module
122+
*
123+
*/
124+
void calculateMaxIterationNum(const size_t scene_module_num);
125+
115126
/**
116127
* @brief unregister managers.
117128
* @param node.
@@ -398,11 +409,13 @@ class PlannerManager
398409
* @brief run all modules in approved_module_ptrs_ and get a planning result as
399410
* approved_modules_output.
400411
* @param planner data.
412+
* @param deleted modules.
401413
* @return valid planning result.
402414
* @details in this function, expired modules (ModuleStatus::FAILURE or ModuleStatus::SUCCESS) are
403-
* removed from approved_module_ptrs_.
415+
* removed from approved_module_ptrs_ and added to deleted_modules.
404416
*/
405-
BehaviorModuleOutput runApprovedModules(const std::shared_ptr<PlannerData> & data);
417+
BehaviorModuleOutput runApprovedModules(
418+
const std::shared_ptr<PlannerData> & data, std::vector<SceneModulePtr> & deleted_modules);
406419

407420
/**
408421
* @brief select a module that should be execute at first.
@@ -422,10 +435,12 @@ class PlannerManager
422435
/**
423436
* @brief get all modules that make execution request.
424437
* @param decided (=approved) path.
438+
* @param deleted modules.
425439
* @return request modules.
426440
*/
427441
std::vector<SceneModulePtr> getRequestModules(
428-
const BehaviorModuleOutput & previous_module_output) const;
442+
const BehaviorModuleOutput & previous_module_output,
443+
const std::vector<SceneModulePtr> & deleted_modules) const;
429444

430445
/**
431446
* @brief checks whether a path of trajectory has forward driving direction

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -70,16 +70,18 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
7070

7171
const std::lock_guard<std::mutex> lock(mutex_manager_); // for planner_manager_
7272

73-
const auto & p = planner_data_->parameters;
74-
planner_manager_ = std::make_shared<PlannerManager>(*this, p.max_iteration_num);
73+
planner_manager_ = std::make_shared<PlannerManager>(*this);
7574

75+
size_t scene_module_num = 0;
7676
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
7777
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
7878
if (name == "") {
7979
break;
8080
}
8181
planner_manager_->launchScenePlugin(*this, name);
82+
scene_module_num++;
8283
}
84+
planner_manager_->calculateMaxIterationNum(scene_module_num);
8385

8486
for (const auto & manager : planner_manager_->getSceneModuleManagers()) {
8587
path_candidate_publishers_.emplace(
@@ -147,7 +149,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
147149
{
148150
BehaviorPathPlannerParameters p{};
149151

150-
p.max_iteration_num = declare_parameter<int>("max_iteration_num");
151152
p.traffic_light_signal_timeout = declare_parameter<double>("traffic_light_signal_timeout");
152153

153154
// vehicle info

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

+33-7
Original file line numberDiff line numberDiff line change
@@ -30,13 +30,12 @@
3030

3131
namespace autoware::behavior_path_planner
3232
{
33-
PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num)
33+
PlannerManager::PlannerManager(rclcpp::Node & node)
3434
: plugin_loader_(
3535
"autoware_behavior_path_planner",
3636
"autoware::behavior_path_planner::SceneModuleManagerInterface"),
3737
logger_(node.get_logger().get_child("planner_manager")),
38-
clock_(*node.get_clock()),
39-
max_iteration_num_{max_iteration_num}
38+
clock_(*node.get_clock())
4039
{
4140
processing_time_.emplace("total_time", 0.0);
4241
debug_publisher_ptr_ = std::make_unique<DebugPublisher>(&node, "~/debug");
@@ -66,6 +65,11 @@ void PlannerManager::launchScenePlugin(rclcpp::Node & node, const std::string &
6665
}
6766
}
6867

68+
void PlannerManager::calculateMaxIterationNum(const size_t scene_module_num)
69+
{
70+
max_iteration_num_ = scene_module_num * (scene_module_num + 1) / 2;
71+
}
72+
6973
void PlannerManager::removeScenePlugin(rclcpp::Node & node, const std::string & name)
7074
{
7175
auto it = std::remove_if(manager_ptrs_.begin(), manager_ptrs_.end(), [&](const auto plugin) {
@@ -127,17 +131,19 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr<PlannerData> & da
127131
"Ego is out of route, no module is running. Skip running scene modules.");
128132
return output;
129133
}
134+
std::vector<SceneModulePtr>
135+
deleted_modules; // store the scene modules deleted from approved modules
130136

131137
for (size_t itr_num = 1;; ++itr_num) {
132138
/**
133139
* STEP1: get approved modules' output
134140
*/
135-
auto approved_modules_output = runApprovedModules(data);
141+
auto approved_modules_output = runApprovedModules(data, deleted_modules);
136142

137143
/**
138144
* STEP2: check modules that need to be launched
139145
*/
140-
const auto request_modules = getRequestModules(approved_modules_output);
146+
const auto request_modules = getRequestModules(approved_modules_output, deleted_modules);
141147

142148
/**
143149
* STEP3: if there is no module that need to be launched, return approved modules' output
@@ -250,7 +256,8 @@ void PlannerManager::generateCombinedDrivableArea(
250256
}
251257

252258
std::vector<SceneModulePtr> PlannerManager::getRequestModules(
253-
const BehaviorModuleOutput & previous_module_output) const
259+
const BehaviorModuleOutput & previous_module_output,
260+
const std::vector<SceneModulePtr> & deleted_modules) const
254261
{
255262
if (previous_module_output.path.points.empty()) {
256263
RCLCPP_ERROR_STREAM(
@@ -268,6 +275,18 @@ std::vector<SceneModulePtr> PlannerManager::getRequestModules(
268275

269276
for (const auto & manager_ptr : manager_ptrs_) {
270277
stop_watch_.tic(manager_ptr->name());
278+
/**
279+
* skip the module that is already deleted.
280+
*/
281+
{
282+
const auto name = manager_ptr->name();
283+
const auto find_deleted_module = [&name](const auto & m) { return m->name() == name; };
284+
const auto itr =
285+
std::find_if(deleted_modules.begin(), deleted_modules.end(), find_deleted_module);
286+
if (itr != deleted_modules.end()) {
287+
continue;
288+
}
289+
}
271290

272291
/**
273292
* determine the execution capability of modules based on existing approved modules.
@@ -655,7 +674,8 @@ std::pair<SceneModulePtr, BehaviorModuleOutput> PlannerManager::runRequestModule
655674
return std::make_pair(module_ptr, results.at(module_ptr->name()));
656675
}
657676

658-
BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<PlannerData> & data)
677+
BehaviorModuleOutput PlannerManager::runApprovedModules(
678+
const std::shared_ptr<PlannerData> & data, std::vector<SceneModulePtr> & deleted_modules)
659679
{
660680
std::unordered_map<std::string, BehaviorModuleOutput> results;
661681
BehaviorModuleOutput output = getReferencePath(data);
@@ -771,6 +791,9 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
771791
const auto itr = std::find_if(
772792
approved_module_ptrs_.begin(), approved_module_ptrs_.end(),
773793
[](const auto & m) { return m->getCurrentStatus() == ModuleStatus::FAILURE; });
794+
if (itr != approved_module_ptrs_.end()) {
795+
deleted_modules.push_back(*itr);
796+
}
774797

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

868+
std::copy_if(
869+
itr, approved_module_ptrs_.end(), std::back_inserter(deleted_modules), success_module_cond);
870+
845871
std::for_each(itr, approved_module_ptrs_.end(), [&](auto & m) {
846872
debug_info_.emplace_back(m, Action::DELETE, "From Approved");
847873
deleteExpiredModules(m);

0 commit comments

Comments
 (0)