Skip to content

Commit ebfba74

Browse files
calculate max_iteration_num from number of scene modules
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 7b46c7f commit ebfba74

File tree

3 files changed

+16
-0
lines changed

3 files changed

+16
-0
lines changed

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

+7
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,13 @@ class PlannerManager
111111
*/
112112
void launchScenePlugin(rclcpp::Node & node, const std::string & name);
113113

114+
/**
115+
* @brief set max iteration numbers
116+
* @param number of scene module
117+
*
118+
*/
119+
void calculateMaxIterationNum(const size_t scene_module_num);
120+
114121
/**
115122
* @brief unregister managers.
116123
* @param node.

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -73,13 +73,16 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod
7373
const auto & p = planner_data_->parameters;
7474
planner_manager_ = std::make_shared<PlannerManager>(*this, p.max_iteration_num);
7575

76+
size_t scene_module_num = 0;
7677
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
7778
// workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter.
7879
if (name == "") {
7980
break;
8081
}
8182
planner_manager_->launchScenePlugin(*this, name);
83+
scene_module_num++;
8284
}
85+
planner_manager_->calculateMaxIterationNum(scene_module_num);
8386

8487
for (const auto & manager : planner_manager_->getSceneModuleManagers()) {
8588
path_candidate_publishers_.emplace(

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,12 @@ void PlannerManager::launchScenePlugin(rclcpp::Node & node, const std::string &
6666
}
6767
}
6868

69+
void PlannerManager::calculateMaxIterationNum(const size_t scene_module_num)
70+
{
71+
max_iteration_num_ = scene_module_num * (scene_module_num + 1) / 2;
72+
73+
}
74+
6975
void PlannerManager::removeScenePlugin(rclcpp::Node & node, const std::string & name)
7076
{
7177
auto it = std::remove_if(manager_ptrs_.begin(), manager_ptrs_.end(), [&](const auto plugin) {

0 commit comments

Comments
 (0)