Skip to content

Commit

Permalink
fix(autoware_behavior_path_planner) : Removed the use of max_iteratio…
Browse files Browse the repository at this point in the history
…n_num parameter.

Signed-off-by: k-hazama-esol <k-hazama@esol.co.jp>
  • Loading branch information
k-hazama-esol committed Feb 28, 2025
1 parent 5c17b3d commit 15be36d
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -367,7 +367,7 @@ class SubPlannerManager
class PlannerManager
{
public:
PlannerManager(rclcpp::Node & node, const size_t max_iteration_num);
PlannerManager(rclcpp::Node & node);

/**
* @brief run all candidate and approved modules.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
{
BehaviorPathPlannerParameters p{};

p.max_iteration_num = declare_parameter<int>("max_iteration_num");
p.traffic_light_signal_timeout = declare_parameter<double>("traffic_light_signal_timeout");

// vehicle info
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,12 @@

namespace autoware::behavior_path_planner
{
PlannerManager::PlannerManager(rclcpp::Node & node, const size_t max_iteration_num)
PlannerManager::PlannerManager(rclcpp::Node & node)
: plugin_loader_(
"autoware_behavior_path_planner",
"autoware::behavior_path_planner::SceneModuleManagerInterface"),
logger_(node.get_logger().get_child("planner_manager")),
clock_(*node.get_clock()),
max_iteration_num_{max_iteration_num}
clock_(*node.get_clock())
{
current_route_lanelet_ = std::make_shared<std::optional<lanelet::ConstLanelet>>(std::nullopt);
processing_time_.emplace("total_time", 0.0);
Expand Down

0 comments on commit 15be36d

Please sign in to comment.