Skip to content

Commit 0521215

Browse files
feat: Remove max_iteration_num parameter from PlannerManager constructor
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 9a1691d commit 0521215

File tree

4 files changed

+4
-8
lines changed

4 files changed

+4
-8
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

+1-1
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ struct SceneModuleStatus
9696
class PlannerManager
9797
{
9898
public:
99-
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num);
99+
explicit PlannerManager(rclcpp::Node & node);
100100

101101
/**
102102
* @brief run all candidate and approved modules.

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,7 @@ 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

7675
size_t scene_module_num = 0;
7776
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
@@ -150,7 +149,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
150149
{
151150
BehaviorPathPlannerParameters p{};
152151

153-
p.max_iteration_num = declare_parameter<int>("max_iteration_num");
154152
p.traffic_light_signal_timeout = declare_parameter<double>("traffic_light_signal_timeout");
155153

156154
// vehicle info

planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp

+2-3
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");

0 commit comments

Comments
 (0)